Only released in EOL distros:  

Package Summary

ROS Wrapper for the KUKA youBot Driver

About

This package provides a ROS wrapper for the Kuka youBot drivers. It includes a joint state publisher and a node called youbot_oodl which publishes to several topics and provides several services for communication with the youBot.

This package has been renamed to youbot_common.

Note that this documentation is not yet complete. Any areas with a question mark (?) are suspicious.

Nodes

youbot_oodl

youbot_oodl is a ROS wrapper for the Kuka youBot drivers. It publishes to several topics and provides several services for communication with the youBot. It can initialize the base and one or two arms for communication, then send messages relaying the state of the arms and odometry data. It can receive velocity commands for the base and arms, and position commands for the arms.

Subscribed Topics

arm_1/arm_controller/follow_joint_trajectory/goal (control_msgs/FollowJointTrajectoryActionGoal)
  • The goal position, velocity, and acceleration for all joints in the move_group for the next step in the trajectory.
arm_1/arm_controller/position_command (brics_actuator/JointPositions)
  • Position setpoint for each arm joint.
arm_1/arm_controller/velocity_command (brics_actuator/JointVelocities)
  • Velocity setpoints for each arm joint.
cmd_vel (geometry_msgs/Twist)
  • Desired velocity for the base
arm_1/gripper_controller/position_command (brics_actuator/JointPositions)
  • Gripper position setpoint.
arm_1/arm_controller/follow_joint_trajectory/cancel (actionlib_msgs/GoalID)
  • Stops the joint trajectory following action with the given GoalID.

Published Topics

arm_1/arm_controller/follow_joint_trajectory/result (control_msgs/FollowJointTrajectoryActionResult)
  • The end status of a follow joint trajectory action, providing the move_group id and the trajectory result as successful or a failure
tf (tf/tfMessage)
  • Transform publisher.
odom (nav_msgs/Odometry)
  • Odometry information. This estimates the robot's current position and orientation in the world relative to its initial position.
diagnostics (diagnostic_msgs/DiagnosticArray)
  • ?- Something to do with diagnostics
arm1/arm_controller/follow_joint_trajectory/feedback (control_msgs/FollowJointTrajectoryActionFeedback)
  • ?- Something to do with how far along a follow joint trajectory action is.
joint_states (sensor_msgs/JointState)
  • The state of each joint.
dashboard/platform_state (youbot_oodl/PowerBoardState)
  • The state of the power board.
arm_1/arm_controller/follow_joint_trajectory/status (actionlib_msgs/GoalStatusArray)
  • The status of the arm controller in relation to its follow-joint-trajectory actions. It consistently outputs the move_group id of the trajectory command and the result text of that trajectory.

Services

base/switchOnMotors (std_srvs/Empty)
  • Switch on the base motors.
base/switchOffMotors (std_srvs/Empty)
  • Switch off the base motors.
arm_1/switchOnMotors (std_srvs/Empty)
  • Switch on the arm motors.
arm_1/switchOffMotors (std_srvs/Empty)
  • Switch off the arm motors.
arm_1/calibrate (std_srvs/Empty)
  • ?- Calibrate the arm. All arm joints return to home position and encoders are zeroed.
reconnect (std_srvs/Empty)
  • Disconnect from the drivers and then reconnect, attempting to keep the current odometry data. This service is called automatically if the etherCAT connection dies.
youbot_oodl/get_loggers (std_srvs/Empty)
  • Prints out the various loggers with their respective logging levels.
youbot_oodl/set_logger_level (std_srvs/Empty)
  • Sets the specified logger to the specified level. For example, rosservice call /youbot_oodl/set_logger_level ros DEBUG will allow ROS_DEBUG messages to appear in the terminal

Parameters

youBotHasBase (bool, default: true)
  • Whether the robot has a base.
youBotHasArms (bool, default: true)
  • Whether the robot has any arms.
youBotDriverCycleFrequencyInHz (double, default: 50.0)
  • The frequency at which the driver should update, in Hz.
trajectoryActionServerEnable (bool, default: true)
  • Whether the trajectory action server should be enabled.
trajectoryPositionGain (double, default: 5.0)
  • The Postion gain for trajectory following.
trajectoryVelocityGain (double, default: 0.0)
  • The Velocity gain for trajectory following.
youBotBaseName (str, default: youbot-base)
  • The name of the base.
youBotArmName1 (str, default: youbot-manipulator)
  • The name of arm 1.
youBotArmName2 (str, default: youbot-manipulator-dual-arm)
  • The name of arm 2.

Installation

youbot_driver

Before installing the package, you must first ensure that youbot_driver is installed, and the environment variable YOUBOT_CONFIG_FOLDER_LOCATION is correctly set to point to the config folder as described in youbot_driver#Installation.

Debian

To install the debian package, do

sudo apt-get install ros-groovy-youbot-oodl 

The debian installation will set the capabilities of the executable by itself, so it will be ready to run immediately after installation.

From Source

To install from source, get the package from the git repository in the typical way. First, create a folder for the package within the src folder of your catkin workspace. cd to the folder, then do

git init
git pull http://github.com/WPI-RAIL/youbot_oodl.git

Go to the root of your catkin workspace and make it.

catkin_make

Then, go to the lib folder containing the youbot_oodl node and set its capabilities so that it will be able to communicate with ethercat.

cd devel/lib/youbot_oodl
sudo setcap cap_net_raw+ep youbot_oodl

You must do this every time you build a new youbot_oodl executable. Otherwise it will give you the following error:

[FATAL] [1370895928.057925761]: No socket connection on eth1
Execute as root
[ERROR] [1370895928.058248099]: Base "youbot-base" could not be initialized.
[ INFO] [1370895928.058573512]: Configuration file path: ,,,,,,/ros-groovy/src/youbot_driver/config/
[FATAL] [1370895928.059439557]: No socket connection on eth1
Execute as root
[ERROR] [1370895928.059770701]: Arm "youbot-manipulator" could not be initialized.
[ INFO] [1370895928.059985361]: System has 0 initialized arm(s).
[ WARN] [1370895928.060813883]: No socket connection on eth1
Execute as root

You will see a similar error if youbot_driver is configured with the wrong ethernet port. If that is the case, it will not say Execute as root. To fix this, go into youbot-ethercat.cfg in the config folder and change EthernetDevice to eth0 or eth1.

Using this Package

Open a terminal on the youBot, either through the OS on the youBot, or by ssh-ing into it. Before running youbot_oodl, make sure the base and arm are on and the arm is in the home configuration. There are notches on each joint to show the home position. When the notch on each side of the joint lines up, that joint is in the correct position. To run youbot_oodl, launch it like so:

roslaunch youbot_oodl youbot_oodl.launch

If all goes well, it should say Base is initialized. and System has 1 initialized arm(s)., among various other things.

There is also a launch file for a robot_state_publisher. This will publish the joint states of the arm. This is useful for visualizing the robot in rviz.

roslaunch youbot_oodl youbot_joint_state_publisher.launch


wpi.png

rail.png

Wiki: youbot_oodl (last edited 2013-08-01 15:09:51 by AndyWolff)