45 #ifndef SAFETY_CONTROLLER_HPP_ 46 #define SAFETY_CONTROLLER_HPP_ 55 #include <std_msgs/Empty.h> 56 #include <geometry_msgs/Twist.h> 57 #include <roch_msgs/CliffEvent.h> 58 #include <roch_msgs/UltEvent.h> 59 #include <roch_msgs/PSDEvent.h> 91 msg_(new geometry_msgs::Twist()){};
101 double time_to_extend_ult_cliff_psd_events;
102 nh_.
param(
"time_to_extend_ult_cliff_psd_events", time_to_extend_ult_cliff_psd_events, 0.0);
138 void enableCB(
const std_msgs::EmptyConstPtr msg);
144 void disableCB(
const std_msgs::EmptyConstPtr msg);
151 void cliffEventCB(
const roch_msgs::CliffEventConstPtr msg);
158 void ultEventCB(
const roch_msgs::UltEventConstPtr msg);
165 void psdEventCB(
const roch_msgs::PSDEventConstPtr msg);
206 if ((msg->leftState == roch_msgs::CliffEvent::CLIFF) || (msg->rightState == roch_msgs::CliffEvent::CLIFF) )
210 if((msg->leftState == roch_msgs::CliffEvent::CLIFF))
212 if((msg->rightState == roch_msgs::CliffEvent::CLIFF))
218 if((msg->leftState == roch_msgs::CliffEvent::FLOOR))
220 if((msg->rightState == roch_msgs::CliffEvent::FLOOR))
227 if ((msg->leftState == roch_msgs::UltEvent::NEAR) || (msg->rightState == roch_msgs::UltEvent::NEAR) || (msg->centerState == roch_msgs::UltEvent::NEAR) )
231 if((msg->leftState == roch_msgs::UltEvent::NEAR))
233 if((msg->centerState == roch_msgs::UltEvent::NEAR))
235 if((msg->rightState == roch_msgs::UltEvent::NEAR))
241 if((msg->leftState == roch_msgs::UltEvent::NORMAL))
243 if((msg->centerState == roch_msgs::UltEvent::NORMAL))
245 if((msg->rightState == roch_msgs::UltEvent::NORMAL))
253 if ((msg->leftState == roch_msgs::PSDEvent::NEAR) || (msg->rightState == roch_msgs::PSDEvent::NEAR) || (msg->centerState == roch_msgs::PSDEvent::NEAR) )
257 if((msg->leftState == roch_msgs::PSDEvent::NEAR))
259 if((msg->centerState == roch_msgs::PSDEvent::NEAR))
261 if((msg->rightState == roch_msgs::PSDEvent::NEAR))
267 if((msg->leftState == roch_msgs::PSDEvent::NORMAL))
269 if((msg->centerState == roch_msgs::PSDEvent::NORMAL))
271 if((msg->rightState == roch_msgs::PSDEvent::NORMAL))
296 msg_.reset(
new geometry_msgs::Twist());
297 msg_->linear.x = -0.1;
298 msg_->linear.y = 0.0;
299 msg_->linear.z = 0.0;
300 msg_->angular.x = 0.0;
301 msg_->angular.y = 0.0;
302 msg_->angular.z = 0.0;
308 msg_.reset(
new geometry_msgs::Twist());
309 msg_->linear.x = -0.1;
310 msg_->linear.y = 0.0;
311 msg_->linear.z = 0.0;
312 msg_->angular.x = 0.0;
313 msg_->angular.y = 0.0;
314 msg_->angular.z = -0.4;
320 msg_.reset(
new geometry_msgs::Twist());
321 msg_->linear.x = -0.1;
322 msg_->linear.y = 0.0;
323 msg_->linear.z = 0.0;
324 msg_->angular.x = 0.0;
325 msg_->angular.y = 0.0;
326 msg_->angular.z = 0.4;
void ultEventCB(const roch_msgs::UltEventConstPtr msg)
Keeps track of ult detection.
void psdEventCB(const roch_msgs::PSDEventConstPtr msg)
Keeps track of PSD detection.
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())
bool psd_center_detected_
ros::Subscriber enable_controller_subscriber_
ros::Subscriber ult_event_subscriber_
ros::Duration time_to_extend_bump_cliff_events_
geometry_msgs::TwistPtr msg_
void cliffEventCB(const roch_msgs::CliffEventConstPtr msg)
Keeps track of cliff detection.
ros::Subscriber psd_event_subscriber_
ros::Time last_event_time_
SafetyController(ros::NodeHandle &nh, std::string &name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Subscriber cliff_event_subscriber_
bool ult_center_detected_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher velocity_command_publisher_
void disableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for disabling the controller.
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool cliff_left_detected_
void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
Callback for resetting safety variables.
ros::Subscriber reset_safety_states_subscriber_
ros::Publisher controller_state_publisher_
ros::Subscriber disable_controller_subscriber_
#define ROS_INFO_STREAM(args)
void enableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for enabling the controller.
bool cliff_right_detected_