safety_controller.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
41 /*****************************************************************************
42 ** Ifdefs
43 *****************************************************************************/
44 
45 #ifndef SAFETY_CONTROLLER_HPP_
46 #define SAFETY_CONTROLLER_HPP_
47 
48 /*****************************************************************************
49 ** Includes
50 *****************************************************************************/
51 
52 #include <string>
53 #include <ros/ros.h>
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>
60 
61 namespace kobuki
62 {
63 
76 {
77 public:
78  SafetyController(ros::NodeHandle& nh, std::string& name) :
79  Controller(),
80  nh_(nh),
81  name_(name),
82  wheel_left_dropped_(false),
83  wheel_right_dropped_(false),
84  bumper_left_pressed_(false),
86  bumper_right_pressed_(false),
87  cliff_left_detected_(false),
89  cliff_right_detected_(false),
90  last_event_time_(ros::Time(0)),
91  msg_(new geometry_msgs::Twist()){};
93 
98  bool init()
99  {
100  //how long to keep sending messages after a bump, cliff, or wheel drop stops
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);
103  time_to_extend_bump_cliff_events_ = ros::Duration(time_to_extend_bump_cliff_events);
108  wheel_event_subscriber_ = nh_.subscribe("events/wheel_drop", 10, &SafetyController::wheelEventCB, this);
110  velocity_command_publisher_ = nh_.advertise< geometry_msgs::Twist >("cmd_vel", 10);
111  return true;
112  };
113 
117  void spin();
118 
119 private:
121  std::string name_;
131 
132  geometry_msgs::TwistPtr msg_; // velocity command
133 
138  void enableCB(const std_msgs::EmptyConstPtr msg);
139 
144  void disableCB(const std_msgs::EmptyConstPtr msg);
145 
150  void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg);
151 
156  void cliffEventCB(const kobuki_msgs::CliffEventConstPtr msg);
157 
162  void wheelEventCB(const kobuki_msgs::WheelDropEventConstPtr msg);
163 
172  void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg);
173 };
174 
175 
176 void SafetyController::enableCB(const std_msgs::EmptyConstPtr msg)
177 {
178  if (this->enable())
179  {
180  ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
181  }
182  else
183  {
184  ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
185  }
186 };
187 
188 void SafetyController::disableCB(const std_msgs::EmptyConstPtr msg)
189 {
190  if (this->disable())
191  {
192  ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
193  }
194  else
195  {
196  ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
197  }
198 };
199 
200 void SafetyController::cliffEventCB(const kobuki_msgs::CliffEventConstPtr msg)
201 {
202  if (msg->state == kobuki_msgs::CliffEvent::CLIFF)
203  {
205  ROS_DEBUG_STREAM("Cliff detected. Moving backwards. [" << name_ << "]");
206  switch (msg->sensor)
207  {
208  case kobuki_msgs::CliffEvent::LEFT: cliff_left_detected_ = true; break;
209  case kobuki_msgs::CliffEvent::CENTER: cliff_center_detected_ = true; break;
210  case kobuki_msgs::CliffEvent::RIGHT: cliff_right_detected_ = true; break;
211  }
212  }
213  else // kobuki_msgs::CliffEvent::FLOOR
214  {
215  ROS_DEBUG_STREAM("Not detecting any cliffs. Resuming normal operation. [" << name_ << "]");
216  switch (msg->sensor)
217  {
218  case kobuki_msgs::CliffEvent::LEFT: cliff_left_detected_ = false; break;
219  case kobuki_msgs::CliffEvent::CENTER: cliff_center_detected_ = false; break;
220  case kobuki_msgs::CliffEvent::RIGHT: cliff_right_detected_ = false; break;
221  }
222  }
223 };
224 
225 void SafetyController::bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
226 {
227  if (msg->state == kobuki_msgs::BumperEvent::PRESSED)
228  {
230  ROS_DEBUG_STREAM("Bumper pressed. Moving backwards. [" << name_ << "]");
231  switch (msg->bumper)
232  {
233  case kobuki_msgs::BumperEvent::LEFT: bumper_left_pressed_ = true; break;
234  case kobuki_msgs::BumperEvent::CENTER: bumper_center_pressed_ = true; break;
235  case kobuki_msgs::BumperEvent::RIGHT: bumper_right_pressed_ = true; break;
236  }
237  }
238  else // kobuki_msgs::BumperEvent::RELEASED
239  {
240  ROS_DEBUG_STREAM("No bumper pressed. Resuming normal operation. [" << name_ << "]");
241  switch (msg->bumper)
242  {
243  case kobuki_msgs::BumperEvent::LEFT: bumper_left_pressed_ = false; break;
244  case kobuki_msgs::BumperEvent::CENTER: bumper_center_pressed_ = false; break;
245  case kobuki_msgs::BumperEvent::RIGHT: bumper_right_pressed_ = false; break;
246  }
247  }
248 };
249 
250 void SafetyController::wheelEventCB(const kobuki_msgs::WheelDropEventConstPtr msg)
251 {
252  if (msg->state == kobuki_msgs::WheelDropEvent::DROPPED)
253  {
254  // need to keep track of both wheels separately
255  if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
256  {
257  ROS_DEBUG_STREAM("Left wheel dropped. [" << name_ << "]");
258  wheel_left_dropped_ = true;
259  }
260  else // kobuki_msgs::WheelDropEvent::RIGHT
261  {
262  ROS_DEBUG_STREAM("Right wheel dropped. [" << name_ << "]");
263  wheel_right_dropped_ = true;
264  }
265  }
266  else // kobuki_msgs::WheelDropEvent::RAISED
267  {
268  // need to keep track of both wheels separately
269  if (msg->wheel == kobuki_msgs::WheelDropEvent::LEFT)
270  {
271  ROS_DEBUG_STREAM("Left wheel raised. [" << name_ << "]");
272  wheel_left_dropped_ = false;
273  }
274  else // kobuki_msgs::WheelDropEvent::RIGHT
275  {
276  ROS_DEBUG_STREAM("Right wheel raised. [" << name_ << "]");
277  wheel_right_dropped_ = false;
278  }
280  {
281  ROS_DEBUG_STREAM("Both wheels raised. Resuming normal operation. [" << name_ << "]");
282  }
283  }
284 };
285 
286 void SafetyController::resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
287 {
288  wheel_left_dropped_ = false;
289  wheel_right_dropped_ = false;
290  bumper_left_pressed_ = false;
291  bumper_center_pressed_ = false;
292  bumper_right_pressed_ = false;
293  cliff_left_detected_ = false;
294  cliff_center_detected_ = false;
295  cliff_right_detected_ = false;
296  ROS_WARN_STREAM("All safety states have been reset to false. [" << name_ << "]");
297 }
298 
300 {
301  if (this->getState())
302  {
304  {
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;
313  }
315  {
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;
324  }
326  {
327  // left bump/cliff; also spin a bit to the right to make escape easier
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;
336  }
338  {
339  // right bump/cliff; also spin a bit to the left to make escape easier
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;
348  }
349  //if we want to extend the safety state and we're within the time, just keep sending msg_
353  }
354  }
355 };
356 
357 } // namespace kobuki
358 
359 #endif /* SAFETY_CONTROLLER_HPP_ */
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_
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_
ros::Subscriber cliff_event_subscriber_
void bumperEventCB(const kobuki_msgs::BumperEventConstPtr msg)
Keeps track of bumps.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Subscriber bumper_event_subscriber_
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_
#define ROS_INFO_STREAM(args)
ros::Subscriber reset_safety_states_subscriber_
static Time now()
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.
ros::Publisher controller_state_publisher_
geometry_msgs::TwistPtr msg_


kobuki_safety_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:45:09