Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00041
00042
00043
00044
00045 #ifndef SAFETY_CONTROLLER_HPP_
00046 #define SAFETY_CONTROLLER_HPP_
00047
00048
00049
00050
00051
00052 #include <string>
00053 #include <ros/ros.h>
00054 #include <yocs_controllers/default_controller.hpp>
00055 #include <std_msgs/Empty.h>
00056 #include <geometry_msgs/Twist.h>
00057 #include <roch_msgs/CliffEvent.h>
00058 #include <roch_msgs/UltEvent.h>
00059 #include <roch_msgs/PSDEvent.h>
00060
00061 namespace sawyer
00062 {
00063
00075 class SafetyController : public yocs::Controller
00076 {
00077 public:
00078 SafetyController(ros::NodeHandle& nh, std::string& name) :
00079 Controller(),
00080 nh_(nh),
00081 name_(name),
00082 cliff_left_detected_(false),
00083 cliff_right_detected_(false),
00084 ult_left_detected_(false),
00085 ult_center_detected_(false),
00086 ult_right_detected_(false),
00087 psd_left_detected_(false),
00088 psd_center_detected_(false),
00089 psd_right_detected_(false),
00090 last_event_time_(ros::Time(0)),
00091 msg_(new geometry_msgs::Twist()){};
00092 ~SafetyController(){};
00093
00098 bool init()
00099 {
00100
00101 double time_to_extend_ult_cliff_psd_events;
00102 nh_.param("time_to_extend_ult_cliff_psd_events", time_to_extend_ult_cliff_psd_events, 0.0);
00103 time_to_extend_bump_cliff_events_ = ros::Duration(time_to_extend_ult_cliff_psd_events);
00104 enable_controller_subscriber_ = nh_.subscribe("enable", 10, &SafetyController::enableCB, this);
00105 disable_controller_subscriber_ = nh_.subscribe("disable", 10, &SafetyController::disableCB, this);
00106 cliff_event_subscriber_ = nh_.subscribe("events/cliff", 10, &SafetyController::cliffEventCB, this);
00107 ult_event_subscriber_ = nh_.subscribe("events/ult", 10, &SafetyController::ultEventCB, this);
00108 psd_event_subscriber_ = nh_.subscribe("events/psd", 10, &SafetyController::psdEventCB, this);
00109 reset_safety_states_subscriber_ = nh_.subscribe("reset", 10, &SafetyController::resetSafetyStatesCB, this);
00110 velocity_command_publisher_ = nh_.advertise< geometry_msgs::Twist >("cmd_vel", 10);
00111 return true;
00112 };
00113
00117 void spin();
00118
00119 private:
00120 ros::NodeHandle nh_;
00121 std::string name_;
00122 ros::Subscriber enable_controller_subscriber_, disable_controller_subscriber_;
00123 ros::Subscriber cliff_event_subscriber_, ult_event_subscriber_, psd_event_subscriber_;
00124 ros::Subscriber reset_safety_states_subscriber_;
00125 ros::Publisher controller_state_publisher_, velocity_command_publisher_;
00126 bool cliff_left_detected_, cliff_right_detected_;
00127 bool ult_left_detected_, ult_center_detected_, ult_right_detected_;
00128 bool psd_left_detected_, psd_center_detected_, psd_right_detected_;
00129 ros::Duration time_to_extend_bump_cliff_events_;
00130 ros::Time last_event_time_;
00131
00132 geometry_msgs::TwistPtr msg_;
00133
00138 void enableCB(const std_msgs::EmptyConstPtr msg);
00139
00144 void disableCB(const std_msgs::EmptyConstPtr msg);
00145
00146
00151 void cliffEventCB(const roch_msgs::CliffEventConstPtr msg);
00152
00153
00158 void ultEventCB(const roch_msgs::UltEventConstPtr msg);
00159
00160
00165 void psdEventCB(const roch_msgs::PSDEventConstPtr msg);
00166
00167
00176 void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg);
00177 };
00178
00179
00180 void SafetyController::enableCB(const std_msgs::EmptyConstPtr msg)
00181 {
00182 if (this->enable())
00183 {
00184 ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
00185 }
00186 else
00187 {
00188 ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
00189 }
00190 };
00191
00192 void SafetyController::disableCB(const std_msgs::EmptyConstPtr msg)
00193 {
00194 if (this->disable())
00195 {
00196 ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
00197 }
00198 else
00199 {
00200 ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
00201 }
00202 };
00203
00204 void SafetyController::cliffEventCB(const roch_msgs::CliffEventConstPtr msg)
00205 {
00206 if ((msg->leftState == roch_msgs::CliffEvent::CLIFF) || (msg->rightState == roch_msgs::CliffEvent::CLIFF) )
00207 {
00208 last_event_time_ = ros::Time::now();
00209 ROS_DEBUG_STREAM("Cliff detected. Moving backwards. [" << name_ << "]");
00210 if((msg->leftState == roch_msgs::CliffEvent::CLIFF))
00211 cliff_left_detected_ = true;
00212 if((msg->rightState == roch_msgs::CliffEvent::CLIFF))
00213 cliff_right_detected_ = true;
00214 }
00215 else
00216 {
00217 ROS_DEBUG_STREAM("Not detecting any cliffs. Resuming normal operation. [" << name_ << "]");
00218 if((msg->leftState == roch_msgs::CliffEvent::FLOOR))
00219 cliff_left_detected_ = false;
00220 if((msg->rightState == roch_msgs::CliffEvent::FLOOR))
00221 cliff_right_detected_ = false;
00222 }
00223 };
00224
00225 void SafetyController::ultEventCB(const roch_msgs::UltEventConstPtr msg)
00226 {
00227 if ((msg->leftState == roch_msgs::UltEvent::NEAR) || (msg->rightState == roch_msgs::UltEvent::NEAR) || (msg->centerState == roch_msgs::UltEvent::NEAR) )
00228 {
00229 last_event_time_ = ros::Time::now();
00230 ROS_DEBUG_STREAM("Ult detected. Moving backwards. [" << name_ << "]");
00231 if((msg->leftState == roch_msgs::UltEvent::NEAR))
00232 ult_left_detected_ = true;
00233 if((msg->centerState == roch_msgs::UltEvent::NEAR))
00234 ult_center_detected_ = true;
00235 if((msg->rightState == roch_msgs::UltEvent::NEAR))
00236 ult_right_detected_ = true;
00237 }
00238 else
00239 {
00240 ROS_DEBUG_STREAM("Not detecting any cliffs. Resuming normal operation. [" << name_ << "]");
00241 if((msg->leftState == roch_msgs::UltEvent::NORMAL))
00242 ult_left_detected_ = false;
00243 if((msg->centerState == roch_msgs::UltEvent::NORMAL))
00244 ult_center_detected_ = false;
00245 if((msg->rightState == roch_msgs::UltEvent::NORMAL))
00246 ult_right_detected_ = false;
00247 }
00248 };
00249
00250
00251 void SafetyController::psdEventCB(const roch_msgs::PSDEventConstPtr msg)
00252 {
00253 if ((msg->leftState == roch_msgs::PSDEvent::NEAR) || (msg->rightState == roch_msgs::PSDEvent::NEAR) || (msg->centerState == roch_msgs::PSDEvent::NEAR) )
00254 {
00255 last_event_time_ = ros::Time::now();
00256 ROS_DEBUG_STREAM("PSD detected. Moving backwards. [" << name_ << "]");
00257 if((msg->leftState == roch_msgs::PSDEvent::NEAR))
00258 psd_left_detected_ = true;
00259 if((msg->centerState == roch_msgs::PSDEvent::NEAR))
00260 psd_center_detected_ = true;
00261 if((msg->rightState == roch_msgs::PSDEvent::NEAR))
00262 psd_right_detected_ = true;
00263 }
00264 else
00265 {
00266 ROS_DEBUG_STREAM("Not detecting any cliffs. Resuming normal operation. [" << name_ << "]");
00267 if((msg->leftState == roch_msgs::PSDEvent::NORMAL))
00268 psd_left_detected_ = false;
00269 if((msg->centerState == roch_msgs::PSDEvent::NORMAL))
00270 psd_center_detected_ = false;
00271 if((msg->rightState == roch_msgs::PSDEvent::NORMAL))
00272 psd_right_detected_ = false;
00273 }
00274 };
00275
00276
00277 void SafetyController::resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
00278 {
00279 cliff_left_detected_ = false;
00280 cliff_right_detected_ = false;
00281 ult_left_detected_ = false;
00282 ult_center_detected_ = false;
00283 ult_right_detected_ = false;
00284 psd_left_detected_ = false;
00285 psd_center_detected_ = false;
00286 psd_right_detected_ = false;
00287 ROS_WARN_STREAM("All safety states have been reset to false. [" << name_ << "]");
00288 }
00289
00290 void SafetyController::spin()
00291 {
00292 if (this->getState())
00293 {
00294 if ( psd_center_detected_ || ult_center_detected_)
00295 {
00296 msg_.reset(new geometry_msgs::Twist());
00297 msg_->linear.x = -0.1;
00298 msg_->linear.y = 0.0;
00299 msg_->linear.z = 0.0;
00300 msg_->angular.x = 0.0;
00301 msg_->angular.y = 0.0;
00302 msg_->angular.z = 0.0;
00303 velocity_command_publisher_.publish(msg_);
00304 }
00305 else if (cliff_left_detected_ || psd_left_detected_ || ult_left_detected_)
00306 {
00307
00308 msg_.reset(new geometry_msgs::Twist());
00309 msg_->linear.x = -0.1;
00310 msg_->linear.y = 0.0;
00311 msg_->linear.z = 0.0;
00312 msg_->angular.x = 0.0;
00313 msg_->angular.y = 0.0;
00314 msg_->angular.z = -0.4;
00315 velocity_command_publisher_.publish(msg_);
00316 }
00317 else if (cliff_right_detected_ || psd_right_detected_ || ult_right_detected_)
00318 {
00319
00320 msg_.reset(new geometry_msgs::Twist());
00321 msg_->linear.x = -0.1;
00322 msg_->linear.y = 0.0;
00323 msg_->linear.z = 0.0;
00324 msg_->angular.x = 0.0;
00325 msg_->angular.y = 0.0;
00326 msg_->angular.z = 0.4;
00327 velocity_command_publisher_.publish(msg_);
00328 }
00329
00330 if (time_to_extend_bump_cliff_events_ > ros::Duration(1e-10) &&
00331 ros::Time::now() - last_event_time_ < time_to_extend_bump_cliff_events_) {
00332 velocity_command_publisher_.publish(msg_);
00333 }
00334 }
00335 };
00336
00337 }
00338
00339 #endif