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 <xbot_msgs/InfraRed.h>
58 #include <xbot_msgs/Echo.h>
59 namespace xbot
60 {
61 
74 {
75 public:
76  SafetyController(ros::NodeHandle& nh, std::string& name) :
77  Controller(),
78  nh_(nh),
79  name_(name),
80  bumper_front_pressed_(false),
81  bumper_rear_pressed_(false),
82  cliff_front_detected_(false),
83  cliff_rear_detected_(false),
84  last_event_time_(ros::Time(0)),
85  msg_(new geometry_msgs::Twist()){};
87 
92  bool init()
93  {
94  //how long to keep sending messages after a bump, cliff, or wheel drop stops
95  double time_to_extend_bump_cliff_events;
96  nh_.param("time_to_extend_bump_cliff_events", time_to_extend_bump_cliff_events, 0.0);
97  time_to_extend_bump_cliff_events_ = ros::Duration(time_to_extend_bump_cliff_events);
103  velocity_command_publisher_ = nh_.advertise< geometry_msgs::Twist >("cmd_vel", 10);
104  return true;
105  };
106 
110  void spin();
111 
112 private:
114  std::string name_;
123 
124  geometry_msgs::TwistPtr msg_; // velocity command
125 
130  void enableCB(const std_msgs::EmptyConstPtr msg);
131 
136  void disableCB(const std_msgs::EmptyConstPtr msg);
137 
142  void bumperEventCB(const xbot_msgs::EchoConstPtr msg);
143 
148  void cliffEventCB(const xbot_msgs::InfraRedConstPtr msg);
149 
150 
159  void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg);
160 };
161 
162 
163 void SafetyController::enableCB(const std_msgs::EmptyConstPtr msg)
164 {
165  if (this->enable())
166  {
167  ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
168  }
169  else
170  {
171  ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
172  }
173 };
174 
175 void SafetyController::disableCB(const std_msgs::EmptyConstPtr msg)
176 {
177  if (this->disable())
178  {
179  ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
180  }
181  else
182  {
183  ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
184  }
185 };
186 
187 void SafetyController::cliffEventCB(const xbot_msgs::InfraRedConstPtr msg)
188 {
189  if (msg->front_hanged)
190  {
192  ROS_DEBUG_STREAM("Cliff detected. Moving backwards. [" << name_ << "]");
193  cliff_front_detected_ = true;
194  }
195  else{
196  cliff_front_detected_ = false;
197  }
198  if (msg->rear_hanged)
199  {
201  ROS_DEBUG_STREAM("Cliff detected. Moving backwards. [" << name_ << "]");
202  cliff_rear_detected_ = true;
203  }
204  else{
205  cliff_rear_detected_ = false;
206  }
207 
208 
209 };
210 
211 void SafetyController::bumperEventCB(const xbot_msgs::EchoConstPtr msg)
212 {
213  if (msg->front_near)
214  {
216  ROS_DEBUG_STREAM("Bumper pressed. Moving backwards. [" << name_ << "]");
217  bumper_front_pressed_ = true;
218  }
219  else{
220  bumper_front_pressed_ = false;
221  }
222 
223  if (msg->rear_near)
224  {
226  ROS_DEBUG_STREAM("Bumper pressed. Moving backwards. [" << name_ << "]");
227  bumper_rear_pressed_ = true;
228  }
229  else{
230  bumper_rear_pressed_ = false;
231  }
232 
233 
234 };
235 
236 
237 void SafetyController::resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
238 {
239  bumper_front_pressed_ = false;
240  bumper_rear_pressed_ = false;
241  cliff_front_detected_ = false;
242  cliff_rear_detected_ = false;
243  ROS_WARN_STREAM("All safety states have been reset to false. [" << name_ << "]");
244 }
245 
247 {
248  if (this->getState())
249  {
251  {
252  msg_.reset(new geometry_msgs::Twist());
253  msg_->linear.x = -0.1;
254  msg_->linear.y = 0.0;
255  msg_->linear.z = 0.0;
256  msg_->angular.x = 0.0;
257  msg_->angular.y = 0.0;
258  msg_->angular.z = 0.0;
260  }
262  {
263  msg_.reset(new geometry_msgs::Twist());
264  msg_->linear.x = 0.1;
265  msg_->linear.y = 0.0;
266  msg_->linear.z = 0.0;
267  msg_->angular.x = 0.0;
268  msg_->angular.y = 0.0;
269  msg_->angular.z = 0;
271 
272  }
273  //if we want to extend the safety state and we're within the time, just keep sending msg_
277  }
278 
279 };
280 }
281 } // namespace xbot
282 
283 #endif /* SAFETY_CONTROLLER_HPP_ */
ros::Subscriber bumper_event_subscriber_
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())
void enableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for enabling the controller.
ros::Subscriber enable_controller_subscriber_
SafetyController(ros::NodeHandle &nh, std::string &name)
ros::Duration time_to_extend_bump_cliff_events_
void disableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for disabling the controller.
ros::Publisher controller_state_publisher_
void cliffEventCB(const xbot_msgs::InfraRedConstPtr msg)
Keeps track of cliff detection.
ros::Subscriber reset_safety_states_subscriber_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void bumperEventCB(const xbot_msgs::EchoConstPtr msg)
Keeps track of bumps.
geometry_msgs::TwistPtr msg_
ros::Publisher velocity_command_publisher_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
void resetSafetyStatesCB(const std_msgs::EmptyConstPtr msg)
Callback for resetting safety variables.
#define ROS_INFO_STREAM(args)
ros::Subscriber cliff_event_subscriber_
static Time now()
ros::Subscriber disable_controller_subscriber_


xbot_safety_controller
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:27:52