Only released in EOL distros:
Package Summary
Remote User Safety Nodes for CARL
- Maintainer status: maintained
- Maintainer: David Kent <dekent AT gatech DOT edu>
- Author: David Kent <dekent AT gatech DOT edu>, Brian Hetherman <bhetherman AT wpi DOT edu>
- License: BSD
- Bug / feature tracker: https://github.com/GT-RAIL/carl_safety/issues
- Source: git https://github.com/GT-RAIL/carl_safety.git (branch: master)
Contents
About
The carl_safety package contains various nodes for ensuring the safe operation of the CARL robot for both local and remote users. This includes safety features for arm control, autonomous navigation, manual navigation teleoperation, and tipping detection.
Nodes
arm_safety
Provides terminal and audible warnings for when any of the arm's joints exceed a dangerous current threshold.Subscribed Topics
jaco_arm/joint_states (sensor_msgs/JointState)- Joint state updates for the arm.
Parameters
enable_audible_warnings (bool, default: false)- Option for allowing CARL to produce audible warnings for arm joint over-current.
nav_safety
Safety overrides for manual and autonomous navigation, by providing an extra layer to filter move_base and cmd_vel commands from a remote source, preventing them if the arm is in an unsafe position or allowing an operator to temporarily disable these inputs completely.Action Goal
move_base_safe (move_base_msgs/MoveBaseAction)- Safe version of the move_base action server which will not allow the command to be passed on to the move_base action server if the arm is in an unsafe position.
Actions Called
move_base (move_base_msgs/MoveBaseGoal)- Call to the move base action server.
Subscribed Topics
cmd_vel_safe (geometry_msgs/Twist)- An extra layer for cmd_vel commands that can be disabled or enabled for safety reasons; this node will pass commands either directly to cmd_vel or through the cmd_vel_safety_check depending on the use_teleop_safety parameter.
- joystick input, used for reading in commands to disable or enable all navigation commands.
- Robot pose subscriber.
Published Topics
cmd_vel (geometry_msgs/Twist)- Manual base navigation commands.
- Manual base navigation commands with safety check preventing the robot from driving into obstacles on the map. This will replace the cmd_vel publisher if the use_teleop_safety parameter is set to true.
Services
carl_safety/stop_base_nav (std_srvs/Empty)- Stop all autonomous and manual base navigation.
Services Called
jaco_arm/get_angular_position (wpi_jaco_msgs/GetAngularPosition)- Read the angular position of the arm.
- Read the Cartesian position of the arm.
Parameters
controller_type (string, default: digital)- Type of controller used, either "analog" or "digital".
- Option to pass teleop commands through the teleop_safety node.
teleop_safety
Base teleoperation safety layer that prevents the robot from driving into obstacles seen from the navigation map.Subscribed Topics
cmd_vel_safety_check (geometry_msgs/Twist)- Incoming cmd_vel commands to be checked for safety.
- Incoming laser scan data.
- Navigation map.
- Robot pose on navigation map.
Published Topics
cmd_vel (geometry_msgs/Twist)- Base movement commands.
tipping_safety
Base tipping detection and prevention through emergency stop.Subscribed Topics
frame_joint_states (sensor_msgs/JointState)- Filtered orientation of the base relative to the ground, calculated from IMU data.
Services Called
jaco_arm/software_estop (wpi_jaco_msgs/EStop)- Arm software emergency stop.
- Base manual and autonomous navigation emergency stop. Note that this will only stop manual navigation commands that are sent through the nav_safety node.
Parameters
enable_audible_warnings (string, default: false)- Allow CARL to give an audible warning when tipping is detected.
Operation
When using the nav_safety node, a controller is required to input stop and restart commands. With a controller connected, pressing the back button will cut off all manual base teleoperation commands going through the safety node, and all autonomous navigation commands will be canceled. Both manual and autonomous base navigation commands can then be re-enabled by pressing the start button.
Installation
To install the carl_safety package, you can install from source with the following commands:
Startup
The carl_safety package contains safety nodes that are categorized into two groups: basic safety functionality that should always be active, and remote interface safety that only affects users who are not copresent with the robot. As such, the package contains two launch files:
roslaunch carl_safety carl_safety_basic.launch
roslaunch carl_safety carl_safety_interface.launch