From sdk-wiki
Jump to: navigation, search

BaxterSetupInactive.pngTutorialTransitionArrow.pngWorkstationSetupInactive.pngTutorialTransitionArrowActive.pngHelloBaxterActive.png

Description

You've set up your Baxter and Development PC. This tutorial will show you how to communicate with Baxter, moving the arms, and allowing him to say "Hello!" to your lab.

Required Hardware

Step 1: Setup ROS Environment

Upon compilation of our catkin workspace, the generated devel folder in the root of our catkin workspace will contain a setup script which informs the ROS environment of our compiled catkin workspace and the packages therein. The root of the catkin workspace that we created is located at ~/ros_ws.

# Move to root of our catkin workspace
$ cd ~/ros_ws

If the devel folder is not available in the root of your catkin_ws, your catkin/ROS workspace (~/ros_ws) is not yet compiled:

$ source /opt/ros/indigo/setup.bash
$ catkin_make
$ source /opt/ros/hydro/setup.bash
$ catkin_make
$ source /opt/ros/groovy/setup.bash
$ catkin_make

Source ROS Environment Setup Script

# Source baxter.sh script
$ . baxter.sh

Your ROS environment should be preconfigured upon terminal startup.

# Source our generated ROS workspace setup script
$ source devel/setup.bash

Step 2: Verify ROS Connectivity

In this step, we will verify communication to and from Baxter and our development workstation.

Verify ROS Master Ping

The development workstation must be able to resolve the ROS Master (running on Baxter). This is defined by the ROS_MASTER_URI which has been set. This ROS_MASTER_URI is typically the ROBOT_HOSTNAME configured (your robot serial number by default).

# Identify the ROS Master location
$ env | grep ROS_MASTER_URI

The result (example): ROS_MASTER_URI=http://011303P0017.local:11311 011303P0017.local in this case is the location of our ROS Master. The development PC must be able to resolve and communicate with this Master.

Verify ability ping our ROS Master:

$ ping <our ROS Master>
# Example
$ ping 011303P0017.local

View Available ROS Topics

Now that we have identified our ROS Master is available on our network, lets view the available rostopics:

$ rostopic list

Verify Development Workstation Ping

We have verified communication from the development pc to Baxter. Now we will SSH to Baxter and verify communication from Baxter to the development PC.

Baxter must be able to resolve ROS_IP or ROS_HOSTNAME (only one should be set) which has been set.

Identify your ROS_IP or ROS_HOSTNAME set ( ROS_IP was previously recommended):

# Identify your ROS_IP
$ env | grep ROS_IP

The result (example): ROS_IP=192.168.101.99

192.168.101.99 in this case is the IP address which must be resolvable to Baxter and all other ROS processes.

# Identify your ROS_HOSTNAME
$ env | grep ROS_HOSTNAME

The result (example): ROS_HOSTNAME=yoda

yoda in this case is the Hostname which must be resolvable to Baxter and all other ROS processes.

We will now SSH to Baxter and verify the ability to communicate with this development PC. For SSH access, please use the ROS Master (ROBOT_HOSTNAME) identified above.

$ ssh ruser@<our ROS Master>

# Password: rethink

# Example:
$ ssh ruser@011303P0017.local

# Now that we have SSH'd into the robot, verify that we are able to ping back to the development PC
ruser@p99 ~ $ ping <ROS_IP/ROS_HOSTNAME>

# Examples:
# ROS_IP
ruser@p99 ~ $ ping 192.168.101.99
# ROS_HOSTNAME
ruser@p99 ~ $ ping yoda

We can now exit our SSH session on the robot:

ruser@p99 ~ $ exit

Echo a ROS Topic

Now that we have seen the available rostopics, and have verified communication to and from Baxter and our development PC, we can connect to and echo the contents being published to a chosen topic:

Double check that our workspace is still configured correctly:

$ cd ~/ros_ws
$ . baxter.sh
$ cd ~/ros_ws
$ source devel/setup.bash

Echo Baxter's joint_states

$ rostopic echo /robot/joint_states

You should see a continuous stream of Baxter's joint names with measured positions, velocities and torques.

All is well! You have successfully setup communication between your development PC and Baxter.

Step 3: Enable the Robot

A fundamental tool for use when working with Baxter, the enable_robot tool, provided in the baxter_tools SDK package, allows for enabling/disabling/resetting/stopping the robot. Baxter must be enabled in order to actively command any of the motors.

Enable the robot:

$ rosrun baxter_tools enable_robot.py -e

Baxter will now be enabled. The joints will be powered, and Baxter will hold his current joint positions with in a position control loop.

Grabbing Baxter's cuff:

Cuff grasp.png

Enters Baxter's arms into "Zero-G" mode. The position control loop will be released with solely gravity compensation enabled. This allows for intuitive hand-over-hand guidance of the limbs throughout the workspace.

Step 4: Run an Example Program

A number of Baxter example programs are provided which use the baxter_interface package which contains Python modules for Baxter Research Robot development.

Run an example program:

$ rosrun baxter_examples joint_velocity_wobbler.py

This example will simply move the arms to a neutral position, enter into velocity control mode, moving each joint through a random sinusoidal motion. More about this example on the Joint Velocity Wobbler Example Page.

Step 5: Interactively Program Baxter

Time to program Baxter! We will now use an interactive Python Shell to programmatically move the arms.

Make sure Baxter is enabled:

$ rosrun baxter_tools enable_robot.py -e

Start an Interactive Python Shell:

$ python

# Import the necessary Python modules

# rospy - ROS Python API
>>> import rospy

# baxter_interface - Baxter Python API
>>> import baxter_interface

# initialize our ROS node, registering it with the Master
>>> rospy.init_node('Hello_Baxter')

# create an instance of baxter_interface's Limb class
>>> limb = baxter_interface.Limb('right')

# get the right limb's current joint angles
>>> angles = limb.joint_angles()

# print the current joint angles
>>> print angles

# reassign new joint angles (all zeros) which we will later command to the limb
>>> angles['right_s0']=0.0
>>> angles['right_s1']=0.0
>>> angles['right_e0']=0.0
>>> angles['right_e1']=0.0
>>> angles['right_w0']=0.0
>>> angles['right_w1']=0.0
>>> angles['right_w2']=0.0

# print the joint angle command
>>> print angles

# move the right arm to those joint angles
>>> limb.move_to_joint_positions(angles)

# Baxter wants to say hello, let's wave the arm

# store the first wave position 
>>> wave_1 = {'right_s0': -0.459, 'right_s1': -0.202, 'right_e0': 1.807, 'right_e1': 1.714, 'right_w0': -0.906, 'right_w1': -1.545, 'right_w2': -0.276}

# store the second wave position
>>> wave_2 = {'right_s0': -0.395, 'right_s1': -0.202, 'right_e0': 1.831, 'right_e1': 1.981, 'right_w0': -1.979, 'right_w1': -1.100, 'right_w2': -0.448}

# wave three times
>>> for _move in range(3):
...     limb.move_to_joint_positions(wave_1)
...     limb.move_to_joint_positions(wave_2)


# quit
>>> quit()


Congratulations! You have successfully completed the installation tutorials!

Next Steps

You've done it! Now that you've successfully completed the installation guide, there is much more to learn.

Places to start: Learning Area - main stop for digging in deeper.


Trouble?

Please visit our Troubleshooting Section