library.cpp
Go to the documentation of this file.
1 
6 #include <limits>
8 
10 {
11 
12 SafetyController::SafetyController(ros::NodeHandle& nh_priv, const std::string& name) :
13  Controller(),
14  nh_priv_(nh_priv),
15  name_(name),
16  obstacle_detected_(false),
17  reverse_(false),
18  reversing_(false),
19  reversing_start_(ros::Time::now()),
20  reversing_distance_(0.02),
21  reversing_velocity_(0.02),
22  reversing_duration_(0.0)
23 {};
24 
25 
27 {
28  if (!nh_priv_.getParam("reverse", reverse_))
29  {
30  ROS_WARN_STREAM("Safety Controller : no parameter on server for reverse, using default '"
31  << reverse_ << "'");
32  }
33  if (reverse_)
34  {
35  if (!nh_priv_.getParam("reversing_distance", reversing_distance_))
36  {
37  ROS_WARN_STREAM("Safety Controller : no parameter on server for reversing_distance, using default '"
38  << reversing_distance_ << "'");
39  }
40  if (!nh_priv_.getParam("reversing_velocity", reversing_velocity_))
41  {
42  ROS_WARN_STREAM("Safety Controller : no parameter on server for reversing_velocity, using default '"
43  << reversing_distance_ << "'");
44  }
45  }
46 
47  // calculate reversing duration
49 
53  velocity_command_publisher_ = nh_priv_.advertise< geometry_msgs::Twist >("cmd_vel", 10);
54  return true;
55 };
56 
57 void SafetyController::enableCB(const std_msgs::EmptyConstPtr msg)
58 {
59  if (this->enable())
60  {
61  ROS_INFO_STREAM("Controller has been enabled. [" << name_ << "]");
62  }
63  else
64  {
65  ROS_INFO_STREAM("Controller was already enabled. [" << name_ <<"]");
66  }
67 }
68 
69 void SafetyController::disableCB(const std_msgs::EmptyConstPtr msg)
70 {
71  if (this->disable())
72  {
73  ROS_INFO_STREAM("Controller has been disabled. [" << name_ <<"]");
74  }
75  else
76  {
77  ROS_INFO_STREAM("Controller was already disabled. [" << name_ <<"]");
78  }
79 }
80 
81 void SafetyController::rangerCB(const sensor_msgs::RangeConstPtr msg)
82 {
83  if (this->getState())
84  {
85  // readings from a fixed-distance ranger
86  if (msg->range == -std::numeric_limits<double>::infinity()) // -Inf means obstacle detected
87  {
88  obstacle_detected_ = true;
89  }
90  }
91  return;
92 }
93 
95 {
96  if (reversing_)
97  {
99  {
100  reversing_ = false;
101  }
102  else
103  {
104  // reverse
105  cmd_vel_msg_.reset(new geometry_msgs::Twist());
106  cmd_vel_msg_->linear.x = -reversing_velocity_;
107  cmd_vel_msg_->linear.y = 0.0;
108  cmd_vel_msg_->linear.z = 0.0;
109  cmd_vel_msg_->angular.x = 0.0;
110  cmd_vel_msg_->angular.y = 0.0;
111  cmd_vel_msg_->angular.z = 0.0;
113 
114  }
115  }
116  else
117  {
118  if (obstacle_detected_)
119  {
120  // stop
121  cmd_vel_msg_.reset(new geometry_msgs::Twist());
122  cmd_vel_msg_->linear.x = 0.0;
123  cmd_vel_msg_->linear.y = 0.0;
124  cmd_vel_msg_->linear.z = 0.0;
125  cmd_vel_msg_->angular.x = 0.0;
126  cmd_vel_msg_->angular.y = 0.0;
127  cmd_vel_msg_->angular.z = 0.0;
129  obstacle_detected_ = false;
130 
131  // change to reversing, if activated
132  if (reverse_)
133  {
134  reversing_ = true;
136  }
137  }
138  }
139  return;
140 }
141 
142 } // namespace yocs_safety_controller
void publish(const boost::shared_ptr< M > &message) const
void rangerCB(const sensor_msgs::RangeConstPtr msg)
Keeps track of rangers.
Definition: library.cpp:81
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void disableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for disabling the controller.
Definition: library.cpp:69
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
SafetyController(ros::NodeHandle &nh_priv, const std::string &name)
Definition: library.cpp:12
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
void enableCB(const std_msgs::EmptyConstPtr msg)
ROS logging output for enabling the controller.
Definition: library.cpp:57
bool getParam(const std::string &key, std::string &s) const
static Time now()


yocs_safety_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 15:54:01