#include <teleop_safety.h>
Public Member Functions | |
teleop_safety () | |
Constructor. | |
~teleop_safety () | |
Destructor. | |
Private Member Functions | |
void | amcl_pose_cback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &pose) |
void | cmd_vel_safety_check_cback (const geometry_msgs::Twist::ConstPtr &cmd) |
void | map_cback (const nav_msgs::OccupancyGrid::ConstPtr &map) |
void | scan_cback (const sensor_msgs::LaserScan::ConstPtr &scan) |
Private Attributes | |
ros::Subscriber | amcl_pose_sub |
ros::Publisher | cmd_vel_pub |
ros::Subscriber | cmd_vel_safety_check |
double | forward_throttle_safety_factor_base |
ros::Subscriber | map_sub |
ros::NodeHandle | node |
tf::TransformListener * | pListener |
double | reverse_throttle_safety_factor_base |
nav_msgs::OccupancyGrid | savedMap |
ros::Subscriber | scan_sub |
geometry_msgs::Twist | twist |
Definition at line 62 of file teleop_safety.h.
Constructor.
Definition at line 5 of file teleop_safety.cpp.
Destructor.
Definition at line 24 of file teleop_safety.cpp.
void teleop_safety::amcl_pose_cback | ( | const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & | pose | ) | [private] |
amcl_pose topic callback function.
pose | - the message for the amcl_pose topic |
Definition at line 114 of file teleop_safety.cpp.
void teleop_safety::cmd_vel_safety_check_cback | ( | const geometry_msgs::Twist::ConstPtr & | cmd | ) | [private] |
Definition at line 29 of file teleop_safety.cpp.
void teleop_safety::map_cback | ( | const nav_msgs::OccupancyGrid::ConstPtr & | map | ) | [private] |
map topic callback function.
map | - the message for the map topic |
Definition at line 109 of file teleop_safety.cpp.
void teleop_safety::scan_cback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) | [private] |
Scan topic callback function.
scan | - the message for the scan topic |
Definition at line 41 of file teleop_safety.cpp.
ros::Subscriber teleop_safety::amcl_pose_sub [private] |
the amcl_pose topic
Definition at line 108 of file teleop_safety.h.
ros::Publisher teleop_safety::cmd_vel_pub [private] |
cmd_vel publisher for the base
Definition at line 104 of file teleop_safety.h.
subscriber to the cmd_vel topic that should be checked for safety
Definition at line 105 of file teleop_safety.h.
double teleop_safety::forward_throttle_safety_factor_base [private] |
factor for reducing the base maximum positive linear speed from laser scan
Definition at line 113 of file teleop_safety.h.
ros::Subscriber teleop_safety::map_sub [private] |
the map topic
Definition at line 107 of file teleop_safety.h.
ros::NodeHandle teleop_safety::node [private] |
a handle for this ROS node
Definition at line 101 of file teleop_safety.h.
tf::TransformListener* teleop_safety::pListener [private] |
Definition at line 102 of file teleop_safety.h.
double teleop_safety::reverse_throttle_safety_factor_base [private] |
factor for reducing the base maximum negetive linear speed from map
Definition at line 114 of file teleop_safety.h.
nav_msgs::OccupancyGrid teleop_safety::savedMap [private] |
map of allowed speeds
Definition at line 111 of file teleop_safety.h.
ros::Subscriber teleop_safety::scan_sub [private] |
the scan topic
Definition at line 106 of file teleop_safety.h.
geometry_msgs::Twist teleop_safety::twist [private] |
base movement command
Definition at line 110 of file teleop_safety.h.