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

#include <safety_controller.hpp>

Inheritance diagram for sawyer::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 cliffEventCB (const roch_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 psdEventCB (const roch_msgs::PSDEventConstPtr msg)
 Keeps track of PSD detection. More...
 
void resetSafetyStatesCB (const std_msgs::EmptyConstPtr msg)
 Callback for resetting safety variables. More...
 
void ultEventCB (const roch_msgs::UltEventConstPtr msg)
 Keeps track of ult detection. More...
 

Private Attributes

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_
 
bool psd_center_detected_
 
ros::Subscriber psd_event_subscriber_
 
bool psd_left_detected_
 
bool psd_right_detected_
 
ros::Subscriber reset_safety_states_subscriber_
 
ros::Duration time_to_extend_bump_cliff_events_
 
bool ult_center_detected_
 
ros::Subscriber ult_event_subscriber_
 
bool ult_left_detected_
 
bool ult_right_detected_
 
ros::Publisher velocity_command_publisher_
 

Detailed Description

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

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

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

Definition at line 78 of file safety_controller.hpp.

sawyer::SafetyController::~SafetyController ( )
inline

Definition at line 92 of file safety_controller.hpp.

Member Function Documentation

void sawyer::SafetyController::cliffEventCB ( const roch_msgs::CliffEventConstPtr  msg)
private

Keeps track of cliff detection.

Parameters
msgincoming topic message

Definition at line 204 of file safety_controller.hpp.

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

ROS logging output for disabling the controller.

Parameters
msgincoming topic message

Definition at line 192 of file safety_controller.hpp.

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

ROS logging output for enabling the controller.

Parameters
msgincoming topic message

Definition at line 180 of file safety_controller.hpp.

bool sawyer::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 sawyer::SafetyController::psdEventCB ( const roch_msgs::PSDEventConstPtr  msg)
private

Keeps track of PSD detection.

Parameters
msgincoming topic message

Definition at line 251 of file safety_controller.hpp.

void sawyer::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 277 of file safety_controller.hpp.

void sawyer::SafetyController::spin ( )
virtual

@ brief Checks safety states and publishes velocity commands when necessary

Reimplemented from yocs::Controller.

Definition at line 290 of file safety_controller.hpp.

void sawyer::SafetyController::ultEventCB ( const roch_msgs::UltEventConstPtr  msg)
private

Keeps track of ult detection.

Parameters
msgincoming topic message

Definition at line 225 of file safety_controller.hpp.

Member Data Documentation

ros::Subscriber sawyer::SafetyController::cliff_event_subscriber_
private

Definition at line 123 of file safety_controller.hpp.

bool sawyer::SafetyController::cliff_left_detected_
private

Definition at line 126 of file safety_controller.hpp.

bool sawyer::SafetyController::cliff_right_detected_
private

Definition at line 126 of file safety_controller.hpp.

ros::Publisher sawyer::SafetyController::controller_state_publisher_
private

Definition at line 125 of file safety_controller.hpp.

ros::Subscriber sawyer::SafetyController::disable_controller_subscriber_
private

Definition at line 122 of file safety_controller.hpp.

ros::Subscriber sawyer::SafetyController::enable_controller_subscriber_
private

Definition at line 122 of file safety_controller.hpp.

ros::Time sawyer::SafetyController::last_event_time_
private

Definition at line 130 of file safety_controller.hpp.

geometry_msgs::TwistPtr sawyer::SafetyController::msg_
private

Definition at line 132 of file safety_controller.hpp.

std::string sawyer::SafetyController::name_
private

Definition at line 121 of file safety_controller.hpp.

ros::NodeHandle sawyer::SafetyController::nh_
private

Definition at line 120 of file safety_controller.hpp.

bool sawyer::SafetyController::psd_center_detected_
private

Definition at line 128 of file safety_controller.hpp.

ros::Subscriber sawyer::SafetyController::psd_event_subscriber_
private

Definition at line 123 of file safety_controller.hpp.

bool sawyer::SafetyController::psd_left_detected_
private

Definition at line 128 of file safety_controller.hpp.

bool sawyer::SafetyController::psd_right_detected_
private

Definition at line 128 of file safety_controller.hpp.

ros::Subscriber sawyer::SafetyController::reset_safety_states_subscriber_
private

Definition at line 124 of file safety_controller.hpp.

ros::Duration sawyer::SafetyController::time_to_extend_bump_cliff_events_
private

Definition at line 129 of file safety_controller.hpp.

bool sawyer::SafetyController::ult_center_detected_
private

Definition at line 127 of file safety_controller.hpp.

ros::Subscriber sawyer::SafetyController::ult_event_subscriber_
private

Definition at line 123 of file safety_controller.hpp.

bool sawyer::SafetyController::ult_left_detected_
private

Definition at line 127 of file safety_controller.hpp.

bool sawyer::SafetyController::ult_right_detected_
private

Definition at line 127 of file safety_controller.hpp.

ros::Publisher sawyer::SafetyController::velocity_command_publisher_
private

Definition at line 125 of file safety_controller.hpp.


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


roch_safety_controller
Author(s): Marcus Liebhardt , Chen
autogenerated on Mon Jun 10 2019 14:41:24