-
Notifications
You must be signed in to change notification settings - Fork 13
Basic ROS MoveIt! and Gazebo Integration
This tutorial will go through the process of integrating a Gazebo-compatible ROS robot model with MoveIt!, building upon the main tutorial given on the MoveIt! website. MoveIt! installation instructions can be found here. (This tutorial assumes you have a URDF model of your robot, which is already set up to work in Gazebo with launch and world files.) This tutorial assumes you are running Ubuntu 16.04 with ROS Kinetic and Gazebo 7.9 or higher.
A (WIP) working example of a MoveIt! configuration can be found in the AS4SR inmoov_ros repository.
- ROS
- URDF model of your robot
- MoveIt!
- Gazebo
- ROS Kinetic
- MoveIt! for ROS Kinetic
- Gazebo 7.9
To begin, launch the MoveIt! setup assistant and follow the steps listed in the main tutorial. Things to note for this process:
- If your robot is fixed in place, it will not need to have a virtual joint.
- When creating a planning group for a group of several joints in sequence (such as an arm), use the
kinematic chain
option to select the joints. Otherwise define the group by individual joints, links, or both. - Planning groups like grippers or other low DOF groups should have their Kinematic Solver set as "none".
- Robot poses defined in the setup assistant (or manually later) can be called directly when using the MoveIt! API.
- Passive joints are ignored by the path planner.
YOURROBOT_moveit
. Don't forget to build the catkin workspace after generating the package.
You can test the new MoveIt! configuration at this point in RViz using the following command.
roslaunch YOURROBOT_moveit demo.launch
Further steps need to be taken beyond the setup assistant to bring full MoveIt! functionality to the robot model:
First, you will need to create a configuration file for your robot. In the config
directory of the MoveIt! directory create a new file called controllers.yaml
. In this file, create a controller for each of the planning groups you made in the setup assistant like the template below, substituting the names of your robot, planning groups, and joints. Ensure that you give the controller the proper topic name in the name
parameter.
controller_manager_ns: '' controller_list: - name: YOURROBOT/group1_controller action_ns: follow_joint_trajectory type: FollowJointTrajectory default: true joints: - joint_1 - joint_2 - joint_3 - joint_4 - joint_5 ... - name: YOURROBOT/group2_controller action_ns: follow_joint_trajectory type: FollowJointTrajectory default: true joints: - joint_6 - joint_7 - joint_8 ... ...
If your robot has 3D sensor(s) such as a Kinect, you will also need to create a configuration file for it. The file should be named sensors_YOURSENSOR.yaml and should have the following in it:
sensors: - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater point_cloud_topic: DEPTHTOPIC max_range: 5.0 point_subsample: 1 padding_offset: 0.1 padding_scale: 1.0 filtered_cloud_topic: filtered_cloud
Insert the parameters of your sensors into this structure, ensuring that your point_cloud_topic name points to the right topic (as defined in your URDF).
In the MoveIt! launch directory, there will be an empty file called YOURROBOT_moveit_controller_manager.launch.xml
. Copy the following code snippet into, filling in the info specific to your robot:
<launch> # Set the param that trajectory_execution_manager needs to find the controller plugin <arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" /> <param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/> # load controller_list <rosparam file="$(find YOURROBOT_moveit)/config/controllers.yaml"/> </launch>
Next, create a new file called moveit_planning_execution.launch
, which will be the main launch file for MoveIt! and the RViz window while running in parallel with Gazebo. In it, put the following content, again substituting your robot's information:
<launch> # The planning and execution components of MoveIt! configured to # publish the current configuration of the robot (simulated or real) # and the current state of the world as seen by the planner <include file="$(find YOURROBOT_moveit)/launch/move_group.launch"> <arg name="publish_monitored_planning_scene" value="true" /> </include> # The visualization component of MoveIt! <include file="$(find YOURROBOT_moveit)/launch/moveit_rviz.launch"/> </launch>
Finally, replace the contents of the auto-generated file sensor_manager.launch.xml
with the following code.
<launch> # This file makes it easy to include the settings for sensor managers # Sensor configuration files <rosparam command="load" file="$(find YOURROBOT_moveit)/config/sensors_YOURSENSOR.yaml" /> # Params for the octomap monitor <param name="octomap_frame" type="string" value="map" /> <param name="octomap_resolution" type="double" value="0.025" /> <param name="max_range" type="double" value="5.0" /> # Load the robot specific sensor manager; this sets the moveit_sensor_manager ROS parameter <arg name="moveit_sensor_manager" default="YOURROBOT" /> <include file="$(find YOURROBOT_moveit)/launch/$(arg moveit_sensor_manager)_moveit_sensor_manager.launch.xml" /> </launch>
In the YOURROBOT_control
directory, you will need to modify your controller configuration file (probably called something like YOURROBOT_control.yaml
) creating a new controller for each of the planning groups in your MoveIt! configuation, all of the type position_controller/JointTrajectoryController
. The format for these controllers is as shown below:
YOURROBOT: joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 group1_controller: type: position_controllers/JointTrajectoryController joints: - joint_1 - joint_2 - joint_3 - joint_4 - joint_5 ... group2_controller: type: position_controllers/JointTrajectoryController joints: - joint_6 - joint_7 - joint_8 ... ...
It is important that these controllers have the same names and lists of joints as defined in the controllers.yaml
file in the MoveIt! config directory, otherwise MoveIt! cannot communicate with the trajectory controllers. If you have joints that are not defined in the MoveIt! configuration, you can leave them unmodified and listed below in the same file.
Additionally, do not forget to update the controller launch file to reflect these changes to the configuration file.
In your robot's URDF file, change the hardwareTransmission
tags of any transmissions whose corresponding joint is part of a MoveIt! planning group to a PositionJointInterface
:
<transmission name="TRANSNAME"> <type>transmission_interface/SimpleTransmission</type> <joint name="JOINTNAME"> <hardwareInterface>hardware_interface/PositionJointInterface</hardwareinterface> </joint> <actuator name="ACCUATENAME"> <hardwareInterface>hardware_interface/PositionJointInterface</hardwareinterface> <mechanicalReduction>1</mechanicalreduction> </actuator> </transmission>
You should now be able to use Gazebo and RViz together.
First, launch Gazebo using the launch file you created for the robot:
roslaunch YOURROBOT_gazebo YOURROBOT_world.launch
Then, launch RViz and MoveIt! in a new terminal:
roslaunch YOURROBOT_moveit moveit_planning_execution.launch
If all is set up properly, sending execution commands in the RViz GUI will send commands to the robot in Gazebo, and sensor data from the Gazebo model will appear as an octomap in the RViz GUI.
NOTE: in the XML formated files above, replace the comment blocks started with a # to the comment style for xml (this comment style will not display properly in a MediaWiki file.
- In robots with multiple planning groups, you cannot execute two groups separately but at the same time. MoveIt! does not allow this, and will preempt one of the executions. A solution to this is to create a "super-planning group" which contains the two (or more) other groups that you want to execute.
- I have not yet used ROS Melodic or the new version of MoveIt , but it appears that they have streamlined the process of getting Gazebo and MoveIt working together.