safety checks for keyboard navigation More...
#include <keyNavSafety.h>
Public Member Functions | |
void | baseCommandCallback (const geometry_msgs::Twist &requestedCommand) |
void | costCallback (const youbot_overhead_localization::CostmapCost &newCost) |
keyNavSafety () | |
void | localizationCallback (const youbot_overhead_localization::Pose2d &pose) |
Public Attributes | |
ros::Publisher | baseCommandPublisher |
ros::Subscriber | baseCommandSubscriber |
ros::ServiceClient | costClient |
ros::Subscriber | costSubscriber |
youbot_overhead_localization::CostmapCost | currentCost |
time_t | lastStopCmdTime |
bool | localizationInitialized |
ros::Subscriber | localizationSubscriber |
geometry_msgs::Twist | moveCommand |
bool | moveInitialized |
ros::NodeHandle | n |
youbot_overhead_localization::Pose2d | robotPose |
bool | stopCommandFound |
int | timeBetweenStopCmds |
safety checks for keyboard navigation
This class uses costs from the costmap generated for path planning to determine the safety of commands from the keyboard navigation. If the robot is in a dangerous area, the speed is calculated accordingly to prevent damage to the robot or to the environment.
Definition at line 26 of file keyNavSafety.h.
Constructor
This file contains the definition of the keyNavSafety class, which provides checks to make sure the robot does not damage anything while driving freely.
Definition at line 10 of file keyNavSafety.cpp.
void keyNavSafety::baseCommandCallback | ( | const geometry_msgs::Twist & | requestedCommand | ) |
Check a base command for safety and modify it if necessary, then pass it on to the base as a movement command
requestedCommand | the requested move command for the robot base |
Definition at line 107 of file keyNavSafety.cpp.
void keyNavSafety::costCallback | ( | const youbot_overhead_localization::CostmapCost & | newCost | ) |
Update the current cost based on new map information
newCost | updated cost information |
Definition at line 35 of file keyNavSafety.cpp.
void keyNavSafety::localizationCallback | ( | const youbot_overhead_localization::Pose2d & | pose | ) |
Update the robot base localization
pose | the robot base pose |
Definition at line 124 of file keyNavSafety.cpp.
Definition at line 31 of file keyNavSafety.h.
Definition at line 32 of file keyNavSafety.h.
Definition at line 35 of file keyNavSafety.h.
Definition at line 33 of file keyNavSafety.h.
Definition at line 38 of file keyNavSafety.h.
Definition at line 51 of file keyNavSafety.h.
Definition at line 47 of file keyNavSafety.h.
Definition at line 34 of file keyNavSafety.h.
geometry_msgs::Twist keyNavSafety::moveCommand |
Definition at line 41 of file keyNavSafety.h.
Definition at line 46 of file keyNavSafety.h.
Definition at line 30 of file keyNavSafety.h.
Definition at line 44 of file keyNavSafety.h.
Definition at line 50 of file keyNavSafety.h.
Definition at line 52 of file keyNavSafety.h.