Prevents CARL from (manually) driving past a linear boundary on the map. More...
#include <nav_safety.h>
Public Member Functions | |
void | cancelNavGoals () |
cancels all nav goals | |
NavSafety () | |
Constructor. | |
Private Member Functions | |
bool | isArmContained () |
bool | isArmRetracted () |
void | joyCallback (const sensor_msgs::Joy::ConstPtr &joy) |
Joystick input callback. | |
bool | navStopCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
Callback for stopping manual and autonomous navigation from the safe base movement layer. | |
void | poseCallback (const geometry_msgs::Pose::ConstPtr &msg) |
Callback for robot base pose. | |
void | publishArmNotContainedError () |
void | publishClearError () |
void | publishStoppedError () |
void | safeBaseCommandCallback (const geometry_msgs::Twist::ConstPtr &msg) |
Callback for safe base velocity commands. | |
void | safeMoveCallback (const move_base_msgs::MoveBaseGoalConstPtr &goal) |
Layer for safely controlling base movement commands. | |
Private Attributes | |
actionlib::SimpleActionClient < wpi_jaco_msgs::HomeArmAction > | acHome |
actionlib::SimpleActionClient < move_base_msgs::MoveBaseAction > | acMoveBase |
actionlib::SimpleActionServer < move_base_msgs::MoveBaseAction > | asSafeMove |
ros::Publisher | baseCommandPublisher |
ros::Time | baseFeedbackLastPublished |
int | controllerType |
ros::ServiceClient | jacoCartesianClient |
ros::ServiceClient | jacoPosClient |
ros::Subscriber | joySubscriber |
ros::NodeHandle | node |
std::vector< float > | retractPos |
ros::Subscriber | robotPoseSubscriber |
ros::Subscriber | safeBaseCommandSubscriber |
ros::Publisher | safetyErrorPublisher |
ros::ServiceServer | stopBaseNavServer |
bool | stopped |
float | theta |
bool | use_teleop_safety |
float | x |
float | y |
Prevents CARL from (manually) driving past a linear boundary on the map.
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.
Definition at line 47 of file nav_safety.h.
Constructor.
Definition at line 3 of file nav_safety.cpp.
void NavSafety::cancelNavGoals | ( | ) |
cancels all nav goals
Definition at line 154 of file nav_safety.cpp.
bool NavSafety::isArmContained | ( | ) | [private] |
Definition at line 231 of file nav_safety.cpp.
bool NavSafety::isArmRetracted | ( | ) | [private] |
Definition at line 208 of file nav_safety.cpp.
void NavSafety::joyCallback | ( | const sensor_msgs::Joy::ConstPtr & | joy | ) | [private] |
Joystick input callback.
joy | joystick input data |
Definition at line 54 of file nav_safety.cpp.
bool NavSafety::navStopCallback | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) | [private] |
Callback for stopping manual and autonomous navigation from the safe base movement layer.
req | empty service request |
res | empty service response |
Definition at line 200 of file nav_safety.cpp.
void NavSafety::poseCallback | ( | const geometry_msgs::Pose::ConstPtr & | msg | ) | [private] |
Callback for robot base pose.
msg | pose message |
Definition at line 161 of file nav_safety.cpp.
void NavSafety::publishArmNotContainedError | ( | ) | [private] |
Definition at line 245 of file nav_safety.cpp.
void NavSafety::publishClearError | ( | ) | [private] |
Definition at line 263 of file nav_safety.cpp.
void NavSafety::publishStoppedError | ( | ) | [private] |
Definition at line 254 of file nav_safety.cpp.
void NavSafety::safeBaseCommandCallback | ( | const geometry_msgs::Twist::ConstPtr & | msg | ) | [private] |
Callback for safe base velocity commands.
msg | velocity base command |
Definition at line 98 of file nav_safety.cpp.
void NavSafety::safeMoveCallback | ( | const move_base_msgs::MoveBaseGoalConstPtr & | goal | ) | [private] |
Layer for safely controlling base movement commands.
This node will prevent the robot from moving while the arm is extended beyond the navigation footprint of the base; input to this node can also be cut off independently from stopping lower level control, so that external base move commands can be suspended
Definition at line 174 of file nav_safety.cpp.
actionlib::SimpleActionClient<wpi_jaco_msgs::HomeArmAction> NavSafety::acHome [private] |
Definition at line 122 of file nav_safety.h.
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> NavSafety::acMoveBase [private] |
Definition at line 121 of file nav_safety.h.
actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> NavSafety::asSafeMove [private] |
Definition at line 124 of file nav_safety.h.
actual base command publisher
Definition at line 109 of file nav_safety.h.
Definition at line 119 of file nav_safety.h.
int NavSafety::controllerType [private] |
Definition at line 126 of file nav_safety.h.
Definition at line 116 of file nav_safety.h.
ros::ServiceClient NavSafety::jacoPosClient [private] |
Definition at line 115 of file nav_safety.h.
ros::Subscriber NavSafety::joySubscriber [private] |
subscriber for joystick input
Definition at line 112 of file nav_safety.h.
ros::NodeHandle NavSafety::node [private] |
a handle for this ROS node
Definition at line 107 of file nav_safety.h.
std::vector<float> NavSafety::retractPos [private] |
Definition at line 131 of file nav_safety.h.
subscriber for the robot base pose
Definition at line 113 of file nav_safety.h.
subscriber for base commands coming from the web
Definition at line 111 of file nav_safety.h.
safety error message publisher
Definition at line 110 of file nav_safety.h.
Definition at line 117 of file nav_safety.h.
bool NavSafety::stopped [private] |
true if safe nav commands should be stopped
Definition at line 127 of file nav_safety.h.
float NavSafety::theta [private] |
Definition at line 130 of file nav_safety.h.
bool NavSafety::use_teleop_safety [private] |
launch param to determine which node to publish to
Definition at line 133 of file nav_safety.h.
float NavSafety::x [private] |
Definition at line 128 of file nav_safety.h.
float NavSafety::y [private] |
Definition at line 129 of file nav_safety.h.