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

#include <safety_controller.hpp>

Inheritance diagram for xbot::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 xbot_msgs::EchoConstPtr msg)
 Keeps track of bumps. More...
 
void cliffEventCB (const xbot_msgs::InfraRedConstPtr 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...
 

Private Attributes

ros::Subscriber bumper_event_subscriber_
 
bool bumper_front_pressed_
 
bool bumper_rear_pressed_
 
ros::Subscriber cliff_event_subscriber_
 
bool cliff_front_detected_
 
bool cliff_rear_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_
 

Detailed Description

@ brief Keeps track of safety-related events and commands Xbot to move accordingly

The SafetyController keeps track of bumper, cliff and wheel drop events. In case of the first two, Xbot is commanded to move back. In the latter case, Xbot 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 73 of file safety_controller.hpp.

Constructor & Destructor Documentation

xbot::SafetyController::SafetyController ( ros::NodeHandle nh,
std::string &  name 
)
inline

Definition at line 76 of file safety_controller.hpp.

xbot::SafetyController::~SafetyController ( )
inline

Definition at line 86 of file safety_controller.hpp.

Member Function Documentation

void xbot::SafetyController::bumperEventCB ( const xbot_msgs::EchoConstPtr  msg)
private

Keeps track of bumps.

Parameters
msgincoming topic message

Definition at line 211 of file safety_controller.hpp.

void xbot::SafetyController::cliffEventCB ( const xbot_msgs::InfraRedConstPtr  msg)
private

Keeps track of cliff detection.

Parameters
msgincoming topic message

Definition at line 187 of file safety_controller.hpp.

void xbot::SafetyController::disableCB ( const std_msgs::EmptyConstPtr  msg)
private

ROS logging output for disabling the controller.

Parameters
msgincoming topic message

Definition at line 175 of file safety_controller.hpp.

void xbot::SafetyController::enableCB ( const std_msgs::EmptyConstPtr  msg)
private

ROS logging output for enabling the controller.

Parameters
msgincoming topic message

Definition at line 163 of file safety_controller.hpp.

bool xbot::SafetyController::init ( )
inlinevirtual

Set-up necessary publishers/subscribers and variables

Returns
true, if successful

Implements yocs::Controller.

Definition at line 92 of file safety_controller.hpp.

void xbot::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 237 of file safety_controller.hpp.

void xbot::SafetyController::spin ( )
virtual

@ brief Checks safety states and publishes velocity commands when necessary

Reimplemented from yocs::Controller.

Definition at line 246 of file safety_controller.hpp.

Member Data Documentation

ros::Subscriber xbot::SafetyController::bumper_event_subscriber_
private

Definition at line 116 of file safety_controller.hpp.

bool xbot::SafetyController::bumper_front_pressed_
private

Definition at line 119 of file safety_controller.hpp.

bool xbot::SafetyController::bumper_rear_pressed_
private

Definition at line 119 of file safety_controller.hpp.

ros::Subscriber xbot::SafetyController::cliff_event_subscriber_
private

Definition at line 116 of file safety_controller.hpp.

bool xbot::SafetyController::cliff_front_detected_
private

Definition at line 120 of file safety_controller.hpp.

bool xbot::SafetyController::cliff_rear_detected_
private

Definition at line 120 of file safety_controller.hpp.

ros::Publisher xbot::SafetyController::controller_state_publisher_
private

Definition at line 118 of file safety_controller.hpp.

ros::Subscriber xbot::SafetyController::disable_controller_subscriber_
private

Definition at line 115 of file safety_controller.hpp.

ros::Subscriber xbot::SafetyController::enable_controller_subscriber_
private

Definition at line 115 of file safety_controller.hpp.

ros::Time xbot::SafetyController::last_event_time_
private

Definition at line 122 of file safety_controller.hpp.

geometry_msgs::TwistPtr xbot::SafetyController::msg_
private

Definition at line 124 of file safety_controller.hpp.

std::string xbot::SafetyController::name_
private

Definition at line 114 of file safety_controller.hpp.

ros::NodeHandle xbot::SafetyController::nh_
private

Definition at line 113 of file safety_controller.hpp.

ros::Subscriber xbot::SafetyController::reset_safety_states_subscriber_
private

Definition at line 117 of file safety_controller.hpp.

ros::Duration xbot::SafetyController::time_to_extend_bump_cliff_events_
private

Definition at line 121 of file safety_controller.hpp.

ros::Publisher xbot::SafetyController::velocity_command_publisher_
private

Definition at line 118 of file safety_controller.hpp.


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


xbot_safety_controller
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:52