ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

What needs to be launched to use publishTrajectoryLine?

asked 2020-04-13 09:10:18 -0500

dschimpf gravatar image

I have a node which determines a trajectory with moveit and I want to be able to display it in rviz.

I belive the publishTrajectoryLine from the rviz_visual_tools is the right tool for this (as found here: http://docs.ros.org/kinetic/api/movei...). I have added a MarkerArray to rviz, which is subscribed to /rviz_visual_tools.

When I use the demo.launch file from ur10_e_moveit_config (which is from fmauch_universal_robot) I am able to see the path in rviz, but when using my own launch file, created based on the instructions found here (https://industrial-training-master.re...) i cannot see anything.

I am using the same node to determine the trajectory and run publishTrajectoryLine in both cases. Because of that my question is: What needs to be launched when wanting to use the publishTrajectoryLine? I assume something gets launched with the demo.launch file but not with my planning_execution.launch

Below my launch file:

<launch>
  <!-- The planning and execution components of MoveIt! configured to run -->
  <!-- using the ROS-Industrial interface. -->

  <!-- Non-standard joint names:
       - Create a file [robot_moveit_config]/config/joint_names.yaml
           controller_joint_names: [joint_1, joint_2, ... joint_N] 
       - Update with joint names for your robot (in order expected by rbt controller)
       - and uncomment the following line: -->
  <rosparam command="load" file="$(find grindcell_moveit_config)/config/joint_names.yaml"/>

  <!-- the "sim" argument controls whether we connect to a Simulated or Real robot -->
  <!--  - if sim=false, a robot_ip argument is required -->
  <arg name="sim" default="true" />
  <arg name="robot_ip" unless="$(arg sim)" />


<!-- load the robot_description parameter before launching ROS-I nodes -->
<include file="$(find grindcell_moveit_config)/launch/planning_context.launch" >
  <arg name="load_robot_description" value="true" />
</include>

  <!-- run the robot simulator and action interface nodes -->
  <group if="$(arg sim)">
    <param name="use_sim_time" value="true"/>
    <!--<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
      <param name="/use_gui" value="false"/> 
      <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
    </node>-->
    <include file="$(find industrial_robot_simulator)/launch/robot_interface_simulator.launch" />
    <node pkg="rosbag" type="play" name="player" output="screen" args=" --clock --loop /home/dan/bagfiles/2020-01-17-13-23-46.bag"/>
  </group>

  <!-- run the "real robot" interface nodes -->
  <!--   - this typically includes: robot_state, motion_interface, and joint_trajectory_action nodes -->
  <!--   - replace these calls with appropriate robot-specific calls or launch files -->
  <group unless="$(arg sim)">
    <include file="$(find example_organization_ur_launch)/launch/ex-ur10-1.launch" />
    <include file="$(find realsense2_camera)/launch/rs_camera.launch">
    <arg name="filters" value="pointcloud" />
      </include>
  </group>

  <!-- publish the robot state (tf transforms) -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

  <include file="$(find grindcell_moveit_config)/launch/move_group.launch">
    <arg name="publish_monitored_planning_scene" value="true" />
  </include>

  <include file="$(find grindcell_moveit_config)/launch/moveit_rviz.launch">
    <arg name="config" value="true"/>
  </include>


</launch>
edit retag flag offensive close merge delete

Comments

Hi, i have the same problem. Have you solved it? Thank you

CesareT gravatar image CesareT  ( 2020-11-13 06:16:34 -0500 )edit

Hello, sadly no. Instead, I iterate through my trajectory and publish a message with line strip markers (visualization_msgs::Marker::LINE_STRIP) and then display them in RVIZ. THis will show the trajectory for linear path plans.

dschimpf gravatar image dschimpf  ( 2020-11-13 12:18:49 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2020-12-21 19:57:04 -0500

realpot gravatar image

In the code try using publishTrajectoryLine() as shown in the docs here, that is, having the End Effector link also as input for the function additionally to the trajectory, joint_model_group and the line color. Here is an example:

visual_tools_->publishTrajectoryLine(my_plan.trajectory_, joint_model_group->getLinkModel("tcp_link"), joint_model_group, rvt::LIME_GREEN);

Where as "tcp_link" is my end effector link name for Moveit. I was having the same problem and this is what worked for me.

edit flag offensive delete link more

Comments

This works for me, thank you :)

Zenzu gravatar image Zenzu  ( 2021-04-25 08:50:53 -0500 )edit

It works for me too. I just wondering why this code, visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group); cannot display trajectory properly as written in moveit_tutorial, maybe I have to look again to my xacro configuration. Anyway, thank you very much.

rizgiak gravatar image rizgiak  ( 2021-08-31 04:19:50 -0500 )edit

This also works for me, thanks!

Thomas_ctn gravatar image Thomas_ctn  ( 2022-02-07 01:20:37 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2020-04-13 09:10:18 -0500

Seen: 412 times

Last updated: Apr 13 '20