Skip to content

New Feature Documentation for 0.7.0

Rob Linsalata edited this page Apr 23, 2014 · 3 revisions

This page is a quick overview of some of the new features in the RSDK v0.7.0 release. Documentation for these features will be incorporated in the main wiki as we smoothly transition from previous version documentation.

Joint Position Movement Speed

Baxter has a parameter that allows the user to control the movement speed of joint position commands on a given arm. This parameter is set as a ratio from 0-1.0, with a default of 0.3. The command for changing this ratio on a given limb is as follows:

$ rostopic pub /robot/limb/<limb>/set_speed_ratio std_msgs/Float64 <speed ratio>

Gripper and Object Mass

The BRR allows the user to set an expected mass for grippers as well as for grasped objects. This involves copying in a portion of a urdf pertaining to those properties.

Gripper Mass

The command for setting the mass for a given gripper is:

$ rostopic pub -1 /robot/end_effector/<limb>_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"urdf\":{ \"name\": \"<limb>_custom_gripper\",  \"link\": [ { \"name\": \"<limb>_hand\" }, { \"name\": \"<limb>_gripper_base\", \"inertial\": { \"mass\": { \"value\": <mass: in kg> }, \"origin\": { \"xyz\": [0.0014, 0.0, 0.074] } } } ] }}"}'

The maximum mass you should set here is 2.27 (~5 lbs) For example, to set the mass of the right gripper to 2.27 kilograms:

$ rostopic pub -1 /robot/end_effector/right_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"urdf\":{ \"name\": \"right_custom_gripper\",  \"link\": [ { \"name\": \"right_hand\" }, { \"name\": \"right_gripper_base\", \"inertial\": { \"mass\": { \"value\": 2.27 }, \"origin\": { \"xyz\": [0.0014, 0.0, 0.074] } } } ] }}"}'

and to set it to zero:

$ rostopic pub -1 /robot/end_effector/right_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"urdf\":{ \"name\": \"right_custom_gripper\",  \"link\": [ { \"name\": \"right_hand\" }, { \"name\": \"right_gripper_base\", \"inertial\": { \"mass\": { \"value\": 0 }, \"origin\": { \"xyz\": [0.0014, 0.0, 0.074] } } } ] }}"}'

Gripped Object mass

This will set the expected weight of a grasped object and will only be noticeable when the updated arm is currently grasping an object. Once again, the maximum mass that should be set is 2.27 kilograms (~5 lbs).

To set the mass of a gripped object:

$ rostopic pub -1 /robot/end_effector/<limb>_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"object\":{ \"name\": \"<limb>_gripper\", \"inertial\": { \"mass\": { \"value\": <mass: in kg> }, \"origin\": { \"xyz\": [0.0, 0.0, 0.0] }, \"inertia\": { \"ixx\": 0.0, \"ixy\": 0.0, \"ixz\": 0.0, \"iyy\": 0.0, \"iyz\": 0.0, \"izz\": 0.0 } } } }}"}'

For example, to set the mass of a picked object to 2.27 kilograms:

$ rostopic pub -1 /robot/end_effector/right_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"object\":{ \"name\": \"right_gripper\", \"inertial\": { \"mass\": { \"value\": 2.27 }, \"origin\": { \"xyz\": [0.0, 0.0, 0.0] }, \"inertia\": { \"ixx\": 0.0, \"ixy\": 0.0, \"ixz\": 0.0, \"iyy\": 0.0, \"iyz\": 0.0, \"izz\": 0.0 } } } }}"}'

and to set it back to 0:

$ rostopic pub -1 /robot/end_effector/right_gripper/command baxter_core_msgs/EndEffectorCommand '{ id : 65664,  command : "configure", args : "{ \"object\":{ \"name\": \"right_gripper\", \"inertial\": { \"mass\": { \"value\": 0.00 }, \"origin\": { \"xyz\": [0.0, 0.0, 0.0] }, \"inertia\": { \"ixx\": 0.0, \"ixy\": 0.0, \"ixz\": 0.0, \"iyy\": 0.0, \"iyz\": 0.0, \"izz\": 0.0 } } } }}"}'

Network Configuration Information

The BRR has a utility for verifying the network configuration on the robot by switching to TTY3 on (attach a keyboard and press Ctrl+Alt+F3). The output should look like this: tty3 display

Disable Gravity Compensation

To disable the gravity compensation on a given arm, you need to publish an empty message at greater than 5hz to the following topic:

/robot/limb/<limb>/suppress_gravity_compensation

The command to suppress gravity compensation on the left arm would be:

$ rostopic pub /robot/limb/left/suppress_gravity_compensation std_msgs/Empty -r 10

The gravity compensation will stay suppressed as long as this is being published

Disable Collision Avoidance

To disable the collision avoidance on a given arm, you need to publish an empty message at greater than 5hz to the following topic:

/robot/limb/<limb>/suppress_collision_avoidance

The command to suppress collision avoidance on the left arm would be:

$ rostopic pub /robot/limb/left/suppress_collision_avoidance std_msgs/Empty -r 10

The collision avoidance will stay suppressed as long as this is being published

Kinect Basics

Install openni for kinect connectivity

$ sudo apt-get install openni-camera openni-launch
$ rospack profile

You may need to reboot the robot to correctly install the camera drivers. To start publishing the kinect camera, run the openni_launch file:

$ roslaunch openni_launch openni.launch

You can now publish a static tf transform for the kinect connected to a frame on the robot like so:

$ rosrun tf static_transform_publisher <x> <y> <z> <qx> <qy> <qz> <qw> <parent frame> /camera_link 50

If you launch rviz and add a camera linked to /camera/rgb/image_color and add a TF obect, deselecting Show Names and Show Axes, you should be able to see the output from the kinect with an icon indicating its relative position to the robot Using the transform:

$ rosrun tf static_transform_publisher 1 0 0 .1 0 0 0 /torso /camera_link 50

Kinect TF example

Clone this wiki locally