Wiki

Only released in EOL distros:  

Package Summary

Remote User Safety Nodes for CARL

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)

Parameters

enable_audible_warnings (bool, default: false) 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)

Actions Called

move_base (move_base_msgs/MoveBaseGoal)

Subscribed Topics

cmd_vel_safe (geometry_msgs/Twist) joy (sensor_msgs/Joy) robot_pose (geometry_msgs/Pose)

Published Topics

cmd_vel (geometry_msgs/Twist) cmd_vel_safety_check (geometry_msgs/Twist)

Services

carl_safety/stop_base_nav (std_srvs/Empty)

Services Called

jaco_arm/get_angular_position (wpi_jaco_msgs/GetAngularPosition) jaco_arm/get_cartesian_position (wpi_jaco_msgs/GetCartesianPosition)

Parameters

controller_type (string, default: digital) use_teleop_safety (bool, default: false)

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) scan (sensor_msgs/LaserScan) map (nav_msgs/OccupancyGrid) amcl_pose (geometry_msgs/PoseWithCovarianceStamped)

Published Topics

cmd_vel (geometry_msgs/Twist)

tipping_safety

Base tipping detection and prevention through emergency stop.

Subscribed Topics

frame_joint_states (sensor_msgs/JointState)

Services Called

jaco_arm/software_estop (wpi_jaco_msgs/EStop) carl_safety/stop_base_nav (std_srvs/Empty)

Parameters

enable_audible_warnings (string, default: false)

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:

Wiki: carl_safety (last edited 2015-02-09 18:58:49 by davidkent)