Running ROS Gazebo and MoveIt Simulation for Revel

Gazebo Simulator and MoveIt Tutorial with Revel

This Gazebo and MoveIt tutorial covers the primary methods for running Revel in a simulated environment in ROS. Simulated environments are only as good as their physical model of the world. Its difficult to model the internal physics of motors and dynamic systems due to latent variables (friction, viscosity, etc).

However, simulation is useful for testing programs quickly, limiting potentially dangerous movements to simulation. It is also useful as a familiarity tool.

ROS has several useful tools already integrated, which we will explore here. We’ll cover several methods of running a robot in simulation:

  • Standalone Gazebo – Run Gazebo and move the arm by sending goals to motor controllers
  • Standalone MoveIt – Use MoveIt in simulation without using Gazebo as a back end
  • Gazebo + MoveIt – Run Gazebo to simulate the world and use MoveIt to plan simulated trajectories

For those unfamiliar with Gazebo or MoveIt, I encourage you to read up on each a bit before continuing.

 

Gazebo (Standlone)

Gazebo is a powerful simulator that attempts to emulate physics and system dynamics more completely. To control Revel in Gazebo, we use ros_control which can be used both in Gazebo on on the actual robot.

To launch a Gazebo simulation, run the following in a terminal

 roslaunch svenzva_simulation gazebo_ros_control.launch run_trajectory:=false

Which will bring up Gazebo simulator and ros_control controllers. With run_trajectory set to false, each joint is running a separate position controller. We can check on the state of the first motor with

rostopic echo /svenzva_controllers/joint_1/state

and can command a joint with

rostopic pub /svenzva_controllers/joint_1/command std_msgs/Float64 "data: 0.5"

which will set the goal parameter of the controller for joint_1 to 0.5 radians. You can see a full list of controllers for all the joints with

rostopic list

MoveIt! (Standalone)

In this section we’ll launch the MoveIt! stack demonstration in stand-alone simulation mode. MoveIt is a very powerful planning framework built into ROS which allow the robot to plan around obstacles in the environment, among other things.

With the svenzva_ros stack installed, launch the svenzva_moveit demo file in simulation mode with:

roslaunch svenzva_moveit demo.launch simulation:=true

This launches MoveIt! and opens a RViz window with MoveIt!’s planning plugins. This is what the RViz window looks like.

 

MoveIt in RViz

We see the arm in its all-zero configuration. Next we can try invoking MoveIt! to make a plan. Click the Planning tab.

MoveIt's planning tab

We can move the arm by clicking and dragging the blue interactive marker near the robot’s gripper. You’ll see the robot in orange follow the marker around. That is the target goal position that MoveIt! will solve for. You can see the current state of the robot in semi-opaque white.

Once you’re ready to plan to the new pose, click the Plan button.

Setting up MoveIt to plan

If MoveIt! was able to plan successfully, you’ll see an outline of the path the arm will take.

MoveIt showing a plan

Finally, we can make the arm actually move to that pose by clicking the Execute button. This will make the simulated arm follow the plan MoveIt! generated.

MoveIt executing plan

Running MoveIt on the Revel robot
The steps for running MoveIt! when the arm is connected are very similar. Running any MoveIt! plans in simulation will translate 1-1 on the real robot, because this simulation does not attempt to emulate dynamics- only kinematics.

You can launch this demo and also control MoveIt! programmatically, ie without needing to specify poses & planning by hand. Instead, you can use the forward and inverse kinematic services exposed by MoveIt! For more information on this, check out MoveIt! documentation.

Gazebo + MoveIt!

We can run Gazebo with MoveIt! if we load the correct controllers through ros_control, which we do through the run_trajectory argument. This time, bring up Gazebo with

roslaunch svenzva_simulation gazebo_ros_control.launch

Now instead of position controllers, a single trajectory controller is brought up for the whole arm. In a separate terminal we can bring up MoveIt! with

roslaunch svenzva_simulation moveit_demo.launch

This launches the same MoveIt! RViz demo as MoveIt tutorial above, but configured to work with Gazebo. You can do the same planning as in the MoveIt tutorial and the arm will be commanded to move in Gazebo.

Simulation Caveats

Using ROS’s ros_control package with Gazebo requires defining PID parameters for each joint, regardless if in position control or trajectory control mode. These will generally be sub-optimal and may give over/under shoot in the simulation.

The simulator isn’t a perfect model of the physical robot and the PID values do not translate directly to using ros_control on the physical robot.

Leave a Reply

Your email address will not be published. Required fields are marked *