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

Moveit use position_trajectory_controller/follow_joint_trajectory in simulation

asked 2020-04-20 06:13:37 -0500

Markus gravatar image

Hey there,

I currently use position_trajectory_controller/follow_joint_trajectory to control a real robot using moveit. It works just fine. Now I also want to communicate with the position_trajectory_controller/follow_joint_trajectory action server in simulation mode (with a simulated robot). However I am not sure how to include that.

  1. Do I have to add the simulated controllers in the .xacro file of the robot description?

    Does anyone have an exaple of simulating a follow_joint_trajectory action server?

So far my simulation launch file looks like this:

 <launch>

  <arg name="pipeline" default="ompl" />

  <arg name="use_gui" default="false" />

  <!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
  <include file="$(find kr30_moveit)/launch/planning_context.launch">
    <arg name="load_robot_description" value="true"/>
  </include>

      <!-- If needed, broadcast static tf for robot root -->
      <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 world base_link" />

      <!-- We do not have a robot connected, so publish fake joint states -->
      <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
        <param name="/use_gui" value="$(arg use_gui)"/>
        <rosparam param="/source_list">[/move_group/fake_controller_joint_states]</rosparam>
      </node>
      <node name="joint_state_desired_publisher" pkg="topic_tools" type="relay" args="joint_states joint_states_desired" />

      <!-- Given the published joint states, publish tf for the robot links -->
      <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />

      <!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) -->
      <include file="$(find kr30_moveit)/launch/move_group.launch">
        <arg name="allow_trajectory_execution" value="true"/>
        <arg name="fake_execution" value="true"/>
        <arg name="info" value="true"/>
        <arg name="debug" value="false"/>
        <arg name="pipeline" value="$(arg pipeline)"  />
      </include>

      <!-- Run Rviz -->
      <node type="rviz" name="rviz" pkg="rviz" args="-d $(find moveit_tutorials)/config/gripper.rviz" />

    </launch>

rostopic list with above file gives:

/attached_collision_object
/clicked_point
/collision_object
/execute_trajectory/cancel
/execute_trajectory/feedback
/execute_trajectory/goal
/execute_trajectory/result
/execute_trajectory/status
/grasps_marker
/head_mount_kinect/depth_registered/points
/initialpose
/joint_states
/joint_states_desired
/move_base_simple/goal
/move_group/cancel
/move_group/display_contacts
/move_group/display_cost_sources
/move_group/display_grasp_markers
/move_group/display_planned_path
/move_group/fake_controller_joint_states
/move_group/feedback
/move_group/filtered_cloud
/move_group/goal
/move_group/monitored_planning_scene
/move_group/motion_plan_request
/move_group/ompl/parameter_descriptions
/move_group/ompl/parameter_updates
/move_group/plan_execution/parameter_descriptions
/move_group/plan_execution/parameter_updates
/move_group/planning_scene_monitor/parameter_descriptions
/move_group/planning_scene_monitor/parameter_updates
/move_group/result
/move_group/sense_for_plan/parameter_descriptions
/move_group/sense_for_plan/parameter_updates
/move_group/status
/move_group/trajectory_execution/parameter_descriptions
/move_group/trajectory_execution/parameter_updates
/pickup/cancel
/pickup/feedback
/pickup/goal
/pickup/result
/pickup/status
/place/cancel
/place/feedback
/place/goal
/place/result
/place/status
/places_marker
/planning_scene
/planning_scene_world
/recognized_object_array
/rosout
/rosout_agg
/rviz/motionplanning_planning_scene_monitor/parameter_descriptions
/rviz/motionplanning_planning_scene_monitor/parameter_updates
/rviz/planningscene_planning_scene_monitor/parameter_descriptions
/rviz/planningscene_planning_scene_monitor/parameter_updates
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/feedback
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update
/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full
/tf
/tf_static
/trajectory_execution_event

Well, I tried to include the joint_trajector action server it like this:

<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find kuka_eki_hw_interface)/config/hardware_controllers.yaml" command="load"/>

<!-- Load standard kuka controller joint names from YAML file to parameter server -->
<rosparam file="$(find kuka_eki_hw_interface)/config/controller_joint_names.yaml" command="load"/> ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-04-20 07:01:33 -0500

Jiawenxing gravatar image

If you want your robot work in gazebo you can follow this tutorial to add a controller in simulation. You need to add some gazebo tag in your .urdf file. Add the

  <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>, the effort_controllers may be  a little bit hard to configure the pid parameter .

than in your .yaml file

    kr60_3_model:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50  

  kr60trajectory_controller:
    type: "position_controllers/JointTrajectoryController"
    joints:
      - joint_1
      - joint_2
      - joint_3
      - joint_4
      - joint_5
      - joint_6

This is my controller launch file. launch a JointTrajectoryController.

    <launch>

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find kr60_3_control)/config/kr60_3_control.yaml" command="load"/>

  <!-- load the controllers -->

  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="screen" ns="/kr60_3_model" args=" joint_state_controller kr60trajectory_controller"/>

  <!-- convert joint states to TF transforms for rviz, etc -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
    respawn="false" output="screen">
    <remap from="/joint_states" to="/kr60_3_model/joint_states" />
  </node>

</launch>
edit flag offensive delete link more

Comments

Thanks of course I need a simulator if I do not have a real robot connected so controlling with jonit_state trajectory needs gazebo moveit and rviz alone cannot handle it.

Markus gravatar image Markus  ( 2020-04-21 07:21:30 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-04-20 06:13:37 -0500

Seen: 572 times

Last updated: Apr 20 '20