Classes | Defines | Functions
teleop_safety.h File Reference
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <std_msgs/Float64.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <tf/transform_listener.h>
#include <nav_msgs/OccupancyGrid.h>
#include <math.h>
#include <unistd.h>
Include dependency graph for teleop_safety.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  teleop_safety

Defines

#define MIN_FORWARD_SAFE_DIST   0.55
#define MIN_REVERSE_SAFE_DIST   0.65
#define START_FORWARD_SAFETY_THROTTLE_DIST   1.25
 Prevents CARL from (manually) driving past a linear boundary on the map.
#define START_REVERSE_SAFETY_THROTTLE_DIST   1.4

Functions

int main (int argc, char **argv)

Define Documentation

#define MIN_FORWARD_SAFE_DIST   0.55

Definition at line 38 of file teleop_safety.h.

#define MIN_REVERSE_SAFE_DIST   0.65

Definition at line 52 of file teleop_safety.h.

Prevents CARL from (manually) driving past a linear boundary on the map.

.h nav_safety creates a ROS node that prevents CARL from crossing a line on the map during manual navigation. The node also adds estop functionality that prevents only online manual navigation commands.

Author:
Brian Hetherman, WPI - bhetherman@wpi.edu
Date:
October 1, 2014

The dist to start throttling forward linear vel for safety.

Definition at line 31 of file teleop_safety.h.

Definition at line 45 of file teleop_safety.h.


Function Documentation

int main ( int  argc,
char **  argv 
)

Creates and runs the teleop_safety node.

Parameters:
argcargument count that is passed to ros::init
argvarguments that are passed to ros::init
Returns:
EXIT_SUCCESS if the node runs correctly

Creates and runs the arm_safety node.

Parameters:
argcargument count that is passed to ros::init
argvarguments that are passed to ros::init
Returns:
EXIT_SUCCESS if the node runs correctly

Definition at line 60 of file arm_safety.cpp.



carl_safety
Author(s): David Kent , Brian Hetherman
autogenerated on Thu Jun 6 2019 19:03:13