safety_controller.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00041 /*****************************************************************************
00042 ** Ifdefs
00043 *****************************************************************************/
00044 
00045 #ifndef SAFETY_CONTROLLER_HPP_
00046 #define SAFETY_CONTROLLER_HPP_
00047 
00048 /*****************************************************************************
00049 ** Includes
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 <kobuki_msgs/BumperEvent.h>
00058 #include <kobuki_msgs/CliffEvent.h>
00059 #include <kobuki_msgs/WheelDropEvent.h>
00060 
00061 namespace kobuki
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     wheel_left_dropped_(false),
00083     wheel_right_dropped_(false),
00084     bumper_left_pressed_(false),
00085     bumper_center_pressed_(false),
00086     bumper_right_pressed_(false),
00087     cliff_left_detected_(false),
00088     cliff_center_detected_(false),
00089     cliff_right_detected_(false){};
00090   ~SafetyController(){};
00091 
00096   bool init()
00097   {
00098     enable_controller_subscriber_ = nh_.subscribe("enable", 10, &SafetyController::enableCB, this);
00099     disable_controller_subscriber_ = nh_.subscribe("disable", 10, &SafetyController::disableCB, this);
00100     bumper_event_subscriber_ = nh_.subscribe("events/bumper", 10, &SafetyController::bumperEventCB, this);
00101     cliff_event_subscriber_  = nh_.subscribe("events/cliff",  10, &SafetyController::cliffEventCB, this);
00102     wheel_event_subscriber_  = nh_.subscribe("events/wheel_drop", 10, &SafetyController::wheelEventCB, this);
00103     reset_safety_states_subscriber_ = nh_.subscribe("reset", 10, &SafetyController::resetSafetyStatesCB, this);
00104     velocity_command_publisher_ = nh_.advertise< geometry_msgs::Twist >("cmd_vel", 10);
00105     return true;
00106   };
00107 
00111   void spin();
00112 
00113 private:
00114   ros::NodeHandle nh_;
00115   std::string name_;
00116   ros::Subscriber enable_controller_subscriber_, disable_controller_subscriber_;
00117   ros::Subscriber bumper_event_subscriber_, cliff_event_subscriber_, wheel_event_subscriber_;
00118   ros::Subscriber reset_safety_states_subscriber_;
00119   ros::Publisher controller_state_publisher_, velocity_command_publisher_;
00120   bool wheel_left_dropped_, wheel_right_dropped_;
00121   bool bumper_left_pressed_, bumper_center_pressed_, bumper_right_pressed_;
00122   bool cliff_left_detected_, cliff_center_detected_, cliff_right_detected_;
00123 
00124   geometry_msgs::TwistPtr msg_; // velocity command
00125 
00130   void enableCB(const std_msgs::EmptyConstPtr msg);
00131 
00136   void disableCB(const std_msgs::EmptyConstPtr msg);
00137 
00142   void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg);
00143 
00148   void cliffEventCB(const kobuki_msgs::CliffEventConstPtr msg);
00149 
00154   void wheelEventCB(const kobuki_msgs::WheelDropEventConstPtr msg);
00155 
00164   void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg);
00165 };
00166 
00167 
00168 void SafetyController::enableCB(const std_msgs::EmptyConstPtr msg)
00169 {
00170   if (this->enable())
00171   {
00172     ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
00173   }
00174   else
00175   {
00176     ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
00177   }
00178 };
00179 
00180 void SafetyController::disableCB(const std_msgs::EmptyConstPtr msg)
00181 {
00182   if (this->disable())
00183   {
00184     ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
00185   }
00186   else
00187   {
00188     ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
00189   }
00190 };
00191 
00192 void SafetyController::cliffEventCB(const kobuki_msgs::CliffEventConstPtr msg)
00193 {
00194   if (msg->state == kobuki_msgs::CliffEvent::CLIFF)
00195   {
00196     ROS_DEBUG_STREAM("Cliff detected. Moving backwards. [" << name_ << "]");
00197     switch (msg->sensor)
00198     {
00199       case kobuki_msgs::CliffEvent::LEFT:    cliff_left_detected_   = true;  break;
00200       case kobuki_msgs::CliffEvent::CENTER:  cliff_center_detected_ = true;  break;
00201       case kobuki_msgs::CliffEvent::RIGHT:   cliff_right_detected_  = true;  break;
00202     }
00203   }
00204   else // kobuki_msgs::CliffEvent::FLOOR
00205   {
00206     ROS_DEBUG_STREAM("Not detecting any cliffs. Resuming normal operation. [" << name_ << "]");
00207     switch (msg->sensor)
00208     {
00209       case kobuki_msgs::CliffEvent::LEFT:    cliff_left_detected_   = false; break;
00210       case kobuki_msgs::CliffEvent::CENTER:  cliff_center_detected_ = false; break;
00211       case kobuki_msgs::CliffEvent::RIGHT:   cliff_right_detected_  = false; break;
00212     }
00213   }
00214 };
00215 
00216 void SafetyController::bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
00217 {
00218   if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
00219   {
00220     ROS_DEBUG_STREAM("Bumper pressed. Moving backwards. [" << name_ << "]");
00221     switch (msg->bumper)
00222     {
00223       case kobuki_msgs::BumperEvent::LEFT:    bumper_left_pressed_   = true;  break;
00224       case kobuki_msgs::BumperEvent::CENTER:  bumper_center_pressed_ = true;  break;
00225       case kobuki_msgs::BumperEvent::RIGHT:   bumper_right_pressed_  = true;  break;
00226     }
00227   }
00228   else // kobuki_msgs::BumperEvent::RELEASED
00229   {
00230     ROS_DEBUG_STREAM("No bumper pressed. Resuming normal operation. [" << name_ << "]");
00231     switch (msg->bumper)
00232     {
00233       case kobuki_msgs::BumperEvent::LEFT:    bumper_left_pressed_   = false; break;
00234       case kobuki_msgs::BumperEvent::CENTER:  bumper_center_pressed_ = false; break;
00235       case kobuki_msgs::BumperEvent::RIGHT:   bumper_right_pressed_  = false; break;
00236     }
00237   }
00238 };
00239 
00240 void SafetyController::wheelEventCB(const kobuki_msgs::WheelDropEventConstPtr msg)
00241 {
00242   if (msg->state == kobuki_msgs::WheelDropEvent::DROPPED)
00243   {
00244     // need to keep track of both wheels separately
00245     if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
00246     {
00247       ROS_DEBUG_STREAM("Left wheel dropped. [" << name_ << "]");
00248       wheel_left_dropped_ = true;
00249     }
00250     else // kobuki_msgs::WheelDropEvent::RIGHT
00251     {
00252       ROS_DEBUG_STREAM("Right wheel dropped. [" << name_ << "]");
00253       wheel_right_dropped_ = true;
00254     }
00255   }
00256   else // kobuki_msgs::WheelDropEvent::RAISED
00257   {
00258     // need to keep track of both wheels separately
00259     if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
00260     {
00261       ROS_DEBUG_STREAM("Left wheel raised. [" << name_ << "]");
00262       wheel_left_dropped_ = false;
00263     }
00264     else // kobuki_msgs::WheelDropEvent::RIGHT
00265     {
00266       ROS_DEBUG_STREAM("Right wheel raised. [" << name_ << "]");
00267       wheel_right_dropped_ = false;
00268     }
00269     if (!wheel_left_dropped_ && !wheel_right_dropped_)
00270     {
00271       ROS_DEBUG_STREAM("Both wheels raised. Resuming normal operation. [" << name_ << "]");
00272     }
00273   }
00274 };
00275 
00276 void SafetyController::resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
00277 {
00278   wheel_left_dropped_    = false;
00279   wheel_right_dropped_   = false;
00280   bumper_left_pressed_   = false;
00281   bumper_center_pressed_ = false;
00282   bumper_right_pressed_  = false;
00283   cliff_left_detected_   = false;
00284   cliff_center_detected_ = false;
00285   cliff_right_detected_  = false;
00286   ROS_WARN_STREAM("All safety states have been reset to false. [" << name_ << "]");
00287 }
00288 
00289 void SafetyController::spin()
00290 {
00291   if (this->getState())
00292   {
00293     if (wheel_left_dropped_ || wheel_right_dropped_)
00294     {
00295       msg_.reset(new geometry_msgs::Twist());
00296       msg_->linear.x = 0.0;
00297       msg_->linear.y = 0.0;
00298       msg_->linear.z = 0.0;
00299       msg_->angular.x = 0.0;
00300       msg_->angular.y = 0.0;
00301       msg_->angular.z = 0.0;
00302       velocity_command_publisher_.publish(msg_);
00303     }
00304     else if (bumper_center_pressed_ || cliff_center_detected_)
00305     {
00306       msg_.reset(new geometry_msgs::Twist());
00307       msg_->linear.x = -0.1;
00308       msg_->linear.y = 0.0;
00309       msg_->linear.z = 0.0;
00310       msg_->angular.x = 0.0;
00311       msg_->angular.y = 0.0;
00312       msg_->angular.z = 0.0;
00313       velocity_command_publisher_.publish(msg_);
00314     }
00315     else if (bumper_left_pressed_ || cliff_left_detected_)
00316     {
00317       // left bump/cliff; also spin a bit to the right to make escape easier
00318       msg_.reset(new geometry_msgs::Twist());
00319       msg_->linear.x = -0.1;
00320       msg_->linear.y = 0.0;
00321       msg_->linear.z = 0.0;
00322       msg_->angular.x = 0.0;
00323       msg_->angular.y = 0.0;
00324       msg_->angular.z = -0.4;
00325       velocity_command_publisher_.publish(msg_);
00326     }
00327     else if (bumper_right_pressed_ || cliff_right_detected_)
00328     {
00329       // right bump/cliff; also spin a bit to the left to make escape easier
00330       msg_.reset(new geometry_msgs::Twist());
00331       msg_->linear.x = -0.1;
00332       msg_->linear.y = 0.0;
00333       msg_->linear.z = 0.0;
00334       msg_->angular.x = 0.0;
00335       msg_->angular.y = 0.0;
00336       msg_->angular.z = 0.4;
00337       velocity_command_publisher_.publish(msg_);
00338     }
00339   }
00340 };
00341 
00342 } // namespace kobuki
00343 
00344 #endif /* SAFETY_CONTROLLER_HPP_ */


kobuki_safety_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Oct 6 2014 01:32:33