#include <safety_controller.hpp>
@ brief Keeps track of safety-related events and commands Kobuki to move accordingly
The SafetyController keeps track of bumper, cliff and wheel drop events. In case of the first two, Kobuki is commanded to move back. In the latter case, Kobuki is stopped. All commands stop when the event condition disappears. In the case of lateral bump/cliff, robot also spins a bit, what makes easier to escape from the risk.
This controller can be enabled/disabled. The safety states (bumper pressed etc.) can be reset. WARNING: Dangerous!
Definition at line 75 of file safety_controller.hpp.
kobuki::SafetyController::SafetyController | ( | ros::NodeHandle & | nh, |
std::string & | name | ||
) | [inline] |
Definition at line 78 of file safety_controller.hpp.
kobuki::SafetyController::~SafetyController | ( | ) | [inline] |
Definition at line 92 of file safety_controller.hpp.
void kobuki::SafetyController::bumperEventCB | ( | const kobuki_msgs::BumperEventConstPtr | msg | ) | [private] |
Keeps track of bumps.
msg | incoming topic message |
Definition at line 225 of file safety_controller.hpp.
void kobuki::SafetyController::cliffEventCB | ( | const kobuki_msgs::CliffEventConstPtr | msg | ) | [private] |
Keeps track of cliff detection.
msg | incoming topic message |
Definition at line 200 of file safety_controller.hpp.
void kobuki::SafetyController::disableCB | ( | const std_msgs::EmptyConstPtr | msg | ) | [private] |
ROS logging output for disabling the controller.
msg | incoming topic message |
Definition at line 188 of file safety_controller.hpp.
void kobuki::SafetyController::enableCB | ( | const std_msgs::EmptyConstPtr | msg | ) | [private] |
ROS logging output for enabling the controller.
msg | incoming topic message |
Definition at line 176 of file safety_controller.hpp.
bool kobuki::SafetyController::init | ( | ) | [inline, virtual] |
Set-up necessary publishers/subscribers and variables
Implements yocs::Controller.
Definition at line 98 of file safety_controller.hpp.
void kobuki::SafetyController::resetSafetyStatesCB | ( | const std_msgs::EmptyConstPtr | msg | ) | [private] |
Callback for resetting safety variables.
Allows resetting bumper, cliff and wheel drop states. DANGEROUS!
msg | incoming topic message |
Definition at line 286 of file safety_controller.hpp.
void kobuki::SafetyController::spin | ( | ) | [virtual] |
@ brief Checks safety states and publishes velocity commands when necessary
Reimplemented from yocs::Controller.
Definition at line 299 of file safety_controller.hpp.
void kobuki::SafetyController::wheelEventCB | ( | const kobuki_msgs::WheelDropEventConstPtr | msg | ) | [private] |
Keeps track of the wheel states.
msg | incoming topic message |
Definition at line 250 of file safety_controller.hpp.
bool kobuki::SafetyController::bumper_center_pressed_ [private] |
Definition at line 127 of file safety_controller.hpp.
Definition at line 123 of file safety_controller.hpp.
bool kobuki::SafetyController::bumper_left_pressed_ [private] |
Definition at line 127 of file safety_controller.hpp.
bool kobuki::SafetyController::bumper_right_pressed_ [private] |
Definition at line 127 of file safety_controller.hpp.
bool kobuki::SafetyController::cliff_center_detected_ [private] |
Definition at line 128 of file safety_controller.hpp.
Definition at line 123 of file safety_controller.hpp.
bool kobuki::SafetyController::cliff_left_detected_ [private] |
Definition at line 128 of file safety_controller.hpp.
bool kobuki::SafetyController::cliff_right_detected_ [private] |
Definition at line 128 of file safety_controller.hpp.
Definition at line 125 of file safety_controller.hpp.
Definition at line 122 of file safety_controller.hpp.
Definition at line 122 of file safety_controller.hpp.
Definition at line 130 of file safety_controller.hpp.
geometry_msgs::TwistPtr kobuki::SafetyController::msg_ [private] |
Definition at line 132 of file safety_controller.hpp.
std::string kobuki::SafetyController::name_ [private] |
Definition at line 121 of file safety_controller.hpp.
ros::NodeHandle kobuki::SafetyController::nh_ [private] |
Definition at line 120 of file safety_controller.hpp.
Definition at line 124 of file safety_controller.hpp.
Definition at line 129 of file safety_controller.hpp.
Definition at line 125 of file safety_controller.hpp.
Definition at line 123 of file safety_controller.hpp.
bool kobuki::SafetyController::wheel_left_dropped_ [private] |
Definition at line 126 of file safety_controller.hpp.
bool kobuki::SafetyController::wheel_right_dropped_ [private] |
Definition at line 126 of file safety_controller.hpp.