Only released in EOL distros:
Package Summary
ROS Wrapper for the KUKA youBot Driver
- Maintainer status: maintained
- Maintainer: Russell Toris <rctoris AT wpi DOT edu>
- Author: Sebastian Blumenthal <blumenthal AT locomotec DOT com>
- License: LGPL 2.1 or BSD
- Bug / feature tracker: https://github.com/WPI-RAIL/youbot_oodl/issues
- Source: git https://github.com/WPI-RAIL/youbot_oodl.git (branch: groovy-devel)
Contents
About
This package provides a ROS wrapper for the Kuka youBot drivers. It includes a joint state publisher and a node called youbot_wrapper which publishes to several topics and provides several services for communication with the youBot. It also has a software emergency stop and a command velocity safety node.
This package has been renamed to youbot_common from youbot_oodl.
Note that this documentation is not yet complete. Any areas with a question mark (?) are suspicious.
Nodes
youbot_wrapper
youbot_wrapper 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.
- Position setpoint for each arm joint.
- Velocity setpoints for each arm joint.
- Desired velocity for the base
- Gripper position setpoint.
- 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
- Transform publisher.
- Odometry information. This estimates the robot's current position and orientation in the world relative to its initial position.
- ?- Something to do with diagnostics
- ?- Something to do with how far along a follow joint trajectory action is.
- The state of each joint.
- The state of the power board.
- 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.
- Switch off the base motors.
- Switch on the arm motors.
- Switch off the arm motors.
- ?- Calibrate the arm. All arm joints return to home position and encoders are zeroed.
- Disconnect from the drivers and then reconnect, attempting to keep the current odometry data. This service is called automatically if the etherCAT connection dies.
- Prints out the various loggers with their respective logging levels.
- Sets the specified logger to the specified level. For example, rosservice call /youbot_wrapper/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.
- Whether the robot has any arms.
- The frequency at which the driver should update, in Hz.
- Whether the trajectory action server should be enabled.
- The Postion gain for trajectory following.
- The Velocity gain for trajectory following.
- The name of the base.
- The name of arm 1.
- The name of arm 2.
youbot_network_estopper
youbot_network_estopper is a node which will perform an emergency stop on the robot if the network is disconnected or the user commands it. It works by listening for a heartbeat signal from the heartbeat_generator. If it does not get a heartbeat within a certain timeout period, it cancels all trajectories the youbot may be following, sends command velocities of zero to the base and arm, and calls the switchOffBase and switchOffArm services of youbot_wrapper. If it receives another heartbeat, it calls the reconnect service of youbot_wrapper in an attempt to restore control to the robot.Subscribed Topics
youbot_network_estopper/heartbeat (std_msgs/Bool)- The heartbeat with a timestamp. This is published at a steady rate of 10Hz. If a heartbeat is not received within half a second of the last, the emergency stop is triggered.
heartbeat_generator
heartbeat_generator simply generates a heartbeat signal until the user cancels it.Published Topics
youbot_network_estopper/heartbeat (std_msgs/Bool)- The heartbeat with a timestamp. This is published at a steady rate of 10Hz.
cmd_vel_safety
cmd_vel_safety listens to an unsafe command velocity from anywhere and a nav_msgs/GridCells message from the navigation stack's local costmap. It uses tf to find the robot's position, then compares it against the received grid to determine the safety of the received command velocity. If the robot's estimated future position is near an obstacle, the command velocity will be limited before being republished as a safe command velocity. youbot_teleopSubscribed Topics
/move_base_node/local_costmap/obstacles (nav_msgs/GridCells)- The local costmap
- A potentially unsafe command velocity. Normal nodes which publish to cmd_vel directly can be remapped to this.
Published Topics
cmd_vel (geometry_msgs/Twist)- The limited command velocity, sent to the robot.
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
(NOT YET AVAILABLE AS youbot_common, see the old youbot_oodl instead) To install the debian package, do
sudo apt-get install ros-groovy-youbot-common
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_wrapper node and set its capabilities so that it will be able to communicate with ethercat.
cd devel/lib/youbot_common sudo setcap cap_net_raw+ep youbot_wrapper
You must do this every time you build a new youbot_wrapper 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
youbot_wrapper
Open a terminal on the youBot, either through the OS on the youBot, or by ssh-ing into it. Before running youbot_wrapper, 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_wrapper, launch it like so:
roslaunch youbot_common youbot_wrapper.launch
If all goes well, it should say Base is initialized. and System has 1 initialized arm(s)., among various other things.
youbot_joint_state_publisher
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_common youbot_joint_state_publisher.launch
Emergency Stopper
Run the youbot_network_estopper on the robot.
rosrun youbot_common youbot_network_estopper
Run the heartbeat_generator on your local machine. Make sure the ROS_MASTER_URI is set to point to the robot.
rosrun youbot_common heartbeat_generator
Now, if the connection between your local machine and the robot dies even for a short time, the robot will stop any movement until it reconnects. Alternately, you can kill the heartbeat generator if you need to stop the robot in a hurry.
Command Velocity Safety
First, make sure you have a local grid being generated. If you run one of the launch files in youbot_navigation, it will be sure to generate a local grid. Remap whatever node would normally generate command velocities from cmd_vel to cmd_vel_unsafe. This is most easily done in a launch file using the <remap> tag. Run the cmd_vel_safety node.
rosrun youbot_common cmd_vel_safety
For an example of a launch file which uses this, see youbot_keyboard_teleop.launch in youbot_teleop.
|
|
|