Overview

The robotino_safety package implements the robotino_safety_node which listens for linear and angular velocities published for Robotino on the robotino_cmd_vel topic and based on the laser scan readings, looks out for potential obstacles and publishes velocities accordingly on the cmd_vel topic.

robotino_safety_ros.png

Note: The obstacle above is visualized in red. The yellow cylinder is the next heading point on the global path and not the obstacle.

The laser scans received are converted to pointclouds. The points from the cloud are checked if they lie in the outer ellipse (as seen in the image above). If any points do lie in the outer ellipse, it means Robotino is approaching an obstacle and it is decelarated. If the obstacle doesn't move away (in case it is not a human or a cat walking by) and approaches the inner ellipse, Robotino continues to decelerate and finally stop if the obstacle touches the inner ellipse.

The radii of the inner and outer ellipses can be varied in the params below.

ROS Nodes

robotino_safety_node

Subscribed Topics

robotino_cmd_vel (geometry_msgs/Twist)
  • A unique cmd_vel topic for Robotino. The velocities published on this topic are monitored by this node so to as to avoid potential collisions.
bumper (std_msgs/Bool)
  • Bumper values from Robotino. In case of a bumper collision, the node shutsdown.
scan (sensor_msgs/LaserScan)
  • Laser scans from Robotino. The scans are used to detect obstacles ahead.

Published Topics

cmd_vel (geometry_msgs/Twist)
  • Linear and angular velocities for Robotino
~inner_ellipse_marker (visualization_msgs/Marker)
  • Visualization marker for the inner ellipse
~outer_ellipse_marker (visualization_msgs/Marker)
  • Visualization marker for the outer ellipse

Parameters

~outer_major_radius (double, default: 0.70)
  • The major radius of the outer ellipse.
~outer_minor_radius (double, default: 0.30)
  • The minor radius of the outer ellipse.
~inner_major_radius (double, default: 0.40)
  • The major radius of the inner ellipse.
~inner_minor_radius (double, default: 0.25)
  • The minor radius of the inner ellipse.
~node_loop_rate (int, default: 20)
  • The loop rate of this node.

Usage

The robotino_safety_node can be launched as follows.

roslaunch robotino_safety robotino_safety_node.launch

Wiki: robotino_safety (last edited 2012-03-27 07:31:04 by HozefaIndorewala)