-
Notifications
You must be signed in to change notification settings - Fork 38
Using gazebo_ros_control for the Jaco arm
You can use the gazebo_ros_control packages to add joint controllers which implement the ros_control hardware interfaces. See also this Gazebo tutorial. Example launch and configuration files used in this wiki page are from the package jaco_arm/jaco_gazebo and jaco_tutorial/jaco_on_table.
There are some limitations with using the gazebo_ros_control
package. It works fine with position controllers, but if you would like to send velocity commands
instead, also position controllers are required. See this wiki page
for more details about this issue.
The current DefaultRobotHWSim implemenation does not support this, you can only use velocity or position
controllers. However, it still works more or less well with velocity commands only (tested on Ubuntu 14.04/Jade),
but it is not a stable solution at this stage.
Note about Gazebo plugin
Ensure that the following gazebo plugin is loaded with the model in the URDF:
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/jaco</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
The example set-up with jaco on the table used in the following already includes this.
You will need to install the ros_control packages. For example on Jade:
sudo apt-get install ros-<distro>-ros-control ros-<distro>-ros-controllers
Also, you have to have the package gazebo_ros_control.
Note for Jade
The library libgazebo_ros_control.so may actually not be included in the Ubuntu repository of gazebo_ros for Jade yet (it was not at the time of writing, January 2016). To fix this, you can load it into your catkin workdpace separately:
cd <your catkin_workspace>/src
git clone https://github.com/ros-simulation/gazebo_ros_pkgs.git
Then, you may delete all folders except gazebo_ros_control (or you may leave them there to overlay your ubuntu packages).
First, load up the jaco simulation and the controllers:
roslaunch jaco_on_table jaco_on_table_gazebo_controlled.launch load_ros_controllers:=true load_velocity_controller:=false
The argument load_ros_controllers triggers loading up the ros_control controllers
instead of using the gazebo_joint_control implementation.
By default, velocity controllers are loaded. If you
would like to use position controllers instead, you can specify the additional
argument load_velocity_controller:=false
. With the ROS controllers, you can either load velocity or
position controllers, so setting this argument to false will automatically select position controllers.
The robot will collapse at first, until the controllers are loaded. You may now control the robot by sending command messages, e.g. with
rostopic pub -1 /jaco/jaco_arm_1_joint_position_controller/command std_msgs/Float64 "data: -1"
or you may use RQT as described in the Gazebo control tutorial.
rosrun rqt_gui rqt_gui
If you would like to try out sending velocity commands instead of position commands:
roslaunch jaco_on_table jaco_on_table_gazebo_controlled.launch load_ros_controllers:=true load_velocity_controller:=true
The argument load_velocity_controller can be skipped as it defaults to true. It can be used to switch between positon and velocity controllers.
The arm should slowly sink down. This is the problem described here with
using velocity commands only.
You can now send velocity commands to the robot, use for example
rostopic pub -1 /jaco/jaco_arm_0_joint_velocity_controller/command std_msgs/Float64 "data: 1"
to make the arm rotate around its first joint. Or, use the RQT gui to publish command messages.
The gazebo_ros_control Gazebo plugin implements a few joint control
methods (EffortJointInterface, PositionJointInterface or VelocityJointInterface; see
also implementation of DefaultRobotHWSim, in particular methods initSim() and writeSim()).
At the time of writing, all of these methods use PID controllers.
A template of the configuration for the Jaco robot
is provided in config/JacoControl.yaml:
rosed jaco_gazebo JacoControl.yaml
This YAML file will be loaded onto the parameter server by the example launch file
jaco_on_table_gazebo_controlled.launch.
When loading velocity controllers, other PID values are used than when
using position controllers.
You can adjust PID values for both position and velocity controllers in the
YAML configuration file.
The jaco_on_table_gazebo_controlled.launch file can also be used as a template to load your own robot with the Jaco arm. You can also change the configuration YAML file to be loaded in this launch file:
rosed jaco_on_table jaco_on_table_gazebo_controlled.launch
Note that this launch file also offers the option to load up the
gazebo_joint_control implementation to control the joints.
So you only need to pay attention to the settings when argument load_ros_controllers:=true
.
After you load up your robot with the jaco arm, you will also need to load the controllers. The jaco_on_table_gazebo_controlled.launch example already does this for you. Similarly, your own launch file can.
You can use a launch file like this for example to load up the position controllers:
<launch>
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find jaco_gazebo)/config/JacoControl.yaml" command="load"/>
<!-- load the controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" ns="/jaco"
args="jaco_arm_0_joint_position_controller
jaco_arm_1_joint_position_controller
jaco_arm_2_joint_position_controller
jaco_arm_3_joint_position_controller
jaco_arm_4_joint_position_controller
jaco_arm_5_joint_position_controller
jaco_finger_joint_0_position_controller
jaco_finger_joint_2_position_controller
jaco_finger_joint_4_position_controller
joint_state_controller"/>
</launch>
Or use the launch file provided in this package as a template / starting point to create your own launch file:
roslaunch jaco_gazebo jaco_control.launch
Note
The Gazebo controller DefaultRobotHWSim has to be loaded from within
a Gazebo model plugin (see also gazebo control tutorial),
for example the one implemented in GazeboRosControlPlugin.
Gazebo "model plugins" have to be loaded from within the URDF file.
The jaco_on_table_gazebo_controlled.launch file
uses urdf/gzplugin_ros_control.urdf.xacro
to load the Gazebo plugin for the Jaco robot on the table.