Public Member Functions | Private Member Functions | Private Attributes | List of all members
kobuki::SafetyController Class Reference

#include <safety_controller.hpp>

Inheritance diagram for kobuki::SafetyController:
Inheritance graph
[legend]

Public Member Functions

bool init ()
 
 SafetyController (ros::NodeHandle &nh, std::string &name)
 
void spin ()
 
 ~SafetyController ()
 
- Public Member Functions inherited from yocs::Controller
 Controller ()
 
bool disable ()
 
bool enable ()
 
bool getState ()
 
virtual ~Controller ()
 

Private Member Functions

void bumperEventCB (const kobuki_msgs::BumperEventConstPtr msg)
 Keeps track of bumps. More...
 
void cliffEventCB (const kobuki_msgs::CliffEventConstPtr msg)
 Keeps track of cliff detection. More...
 
void disableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for disabling the controller. More...
 
void enableCB (const std_msgs::EmptyConstPtr msg)
 ROS logging output for enabling the controller. More...
 
void resetSafetyStatesCB (const std_msgs::EmptyConstPtr msg)
 Callback for resetting safety variables. More...
 
void wheelEventCB (const kobuki_msgs::WheelDropEventConstPtr msg)
 Keeps track of the wheel states. More...
 

Private Attributes

bool bumper_center_pressed_
 
ros::Subscriber bumper_event_subscriber_
 
bool bumper_left_pressed_
 
bool bumper_right_pressed_
 
bool cliff_center_detected_
 
ros::Subscriber cliff_event_subscriber_
 
bool cliff_left_detected_
 
bool cliff_right_detected_
 
ros::Publisher controller_state_publisher_
 
ros::Subscriber disable_controller_subscriber_
 
ros::Subscriber enable_controller_subscriber_
 
ros::Time last_event_time_
 
geometry_msgs::TwistPtr msg_
 
std::string name_
 
ros::NodeHandle nh_
 
ros::Subscriber reset_safety_states_subscriber_
 
ros::Duration time_to_extend_bump_cliff_events_
 
ros::Publisher velocity_command_publisher_
 
ros::Subscriber wheel_event_subscriber_
 
bool wheel_left_dropped_
 
bool wheel_right_dropped_
 

Detailed Description

@ 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.

Constructor & Destructor Documentation

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.

Member Function Documentation

void kobuki::SafetyController::bumperEventCB ( const kobuki_msgs::BumperEventConstPtr  msg)
private

Keeps track of bumps.

Parameters
msgincoming 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.

Parameters
msgincoming 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.

Parameters
msgincoming 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.

Parameters
msgincoming topic message

Definition at line 176 of file safety_controller.hpp.

bool kobuki::SafetyController::init ( )
inlinevirtual

Set-up necessary publishers/subscribers and variables

Returns
true, if successful

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!

Parameters
msgincoming 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.

Parameters
msgincoming topic message

Definition at line 250 of file safety_controller.hpp.

Member Data Documentation

bool kobuki::SafetyController::bumper_center_pressed_
private

Definition at line 127 of file safety_controller.hpp.

ros::Subscriber kobuki::SafetyController::bumper_event_subscriber_
private

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.

ros::Subscriber kobuki::SafetyController::cliff_event_subscriber_
private

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.

ros::Publisher kobuki::SafetyController::controller_state_publisher_
private

Definition at line 125 of file safety_controller.hpp.

ros::Subscriber kobuki::SafetyController::disable_controller_subscriber_
private

Definition at line 122 of file safety_controller.hpp.

ros::Subscriber kobuki::SafetyController::enable_controller_subscriber_
private

Definition at line 122 of file safety_controller.hpp.

ros::Time kobuki::SafetyController::last_event_time_
private

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.

ros::Subscriber kobuki::SafetyController::reset_safety_states_subscriber_
private

Definition at line 124 of file safety_controller.hpp.

ros::Duration kobuki::SafetyController::time_to_extend_bump_cliff_events_
private

Definition at line 129 of file safety_controller.hpp.

ros::Publisher kobuki::SafetyController::velocity_command_publisher_
private

Definition at line 125 of file safety_controller.hpp.

ros::Subscriber kobuki::SafetyController::wheel_event_subscriber_
private

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.


The documentation for this class was generated from the following file:


kobuki_safety_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:45:09