45 #ifndef SAFETY_CONTROLLER_HPP_ 46 #define SAFETY_CONTROLLER_HPP_ 55 #include <std_msgs/Empty.h> 56 #include <geometry_msgs/Twist.h> 57 #include <kobuki_msgs/BumperEvent.h> 58 #include <kobuki_msgs/CliffEvent.h> 59 #include <kobuki_msgs/WheelDropEvent.h> 91 msg_(new geometry_msgs::Twist()){};
101 double time_to_extend_bump_cliff_events;
102 nh_.
param(
"time_to_extend_bump_cliff_events", time_to_extend_bump_cliff_events, 0.0);
138 void enableCB(
const std_msgs::EmptyConstPtr msg);
144 void disableCB(
const std_msgs::EmptyConstPtr msg);
150 void bumperEventCB(
const kobuki_msgs::BumperEventConstPtr msg);
156 void cliffEventCB(
const kobuki_msgs::CliffEventConstPtr msg);
162 void wheelEventCB(
const kobuki_msgs::WheelDropEventConstPtr msg);
202 if (msg->state == kobuki_msgs::CliffEvent::CLIFF)
227 if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
252 if (msg->state == kobuki_msgs::WheelDropEvent::DROPPED)
255 if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
269 if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
305 msg_.reset(
new geometry_msgs::Twist());
306 msg_->linear.x = 0.0;
307 msg_->linear.y = 0.0;
308 msg_->linear.z = 0.0;
309 msg_->angular.x = 0.0;
310 msg_->angular.y = 0.0;
311 msg_->angular.z = 0.0;
316 msg_.reset(
new geometry_msgs::Twist());
317 msg_->linear.x = -0.1;
318 msg_->linear.y = 0.0;
319 msg_->linear.z = 0.0;
320 msg_->angular.x = 0.0;
321 msg_->angular.y = 0.0;
322 msg_->angular.z = 0.0;
328 msg_.reset(
new geometry_msgs::Twist());
329 msg_->linear.x = -0.1;
330 msg_->linear.y = 0.0;
331 msg_->linear.z = 0.0;
332 msg_->angular.x = 0.0;
333 msg_->angular.y = 0.0;
334 msg_->angular.z = -0.4;
340 msg_.reset(
new geometry_msgs::Twist());
341 msg_->linear.x = -0.1;
342 msg_->linear.y = 0.0;
343 msg_->linear.z = 0.0;
344 msg_->angular.x = 0.0;
345 msg_->angular.y = 0.0;
346 msg_->angular.z = 0.4;
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber disable_controller_subscriber_
bool wheel_right_dropped_
ros::Duration time_to_extend_bump_cliff_events_
SafetyController(ros::NodeHandle &nh, std::string &name)
void disableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for disabling the controller.
ros::Subscriber wheel_event_subscriber_
ros::Publisher velocity_command_publisher_
bool cliff_center_detected_
ros::Subscriber cliff_event_subscriber_
void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
Keeps track of bumps.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Subscriber bumper_event_subscriber_
ros::Time last_event_time_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void enableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for enabling the controller.
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ros::Subscriber enable_controller_subscriber_
bool cliff_left_detected_
bool bumper_left_pressed_
#define ROS_INFO_STREAM(args)
ros::Subscriber reset_safety_states_subscriber_
void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
Callback for resetting safety variables.
void cliffEventCB(const kobuki_msgs::CliffEventConstPtr msg)
Keeps track of cliff detection.
void wheelEventCB(const kobuki_msgs::WheelDropEventConstPtr msg)
Keeps track of the wheel states.
bool cliff_right_detected_
ros::Publisher controller_state_publisher_
bool bumper_center_pressed_
geometry_msgs::TwistPtr msg_
bool bumper_right_pressed_