follower.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
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 the Willow Garage, Inc. 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 
30 #include <ros/ros.h>
32 #include <nodelet/nodelet.h>
33 #include <geometry_msgs/Twist.h>
34 #include <pcl_ros/point_cloud.h>
35 #include <pcl/point_types.h>
36 #include <visualization_msgs/Marker.h>
37 // #include <turtlebot_msgs/SetFollowState.h>
38 
39 #include "dynamic_reconfigure/server.h"
40 #include "oculusprime/FollowerConfig.h"
41 
42 
43 namespace oculusprime
44 {
45 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
46 
47 //* The oculusprime follower nodelet.
54 {
55 public:
61  min_x_(-0.35), max_x_(0.35),
62  max_z_(1.3), goal_z_(0.7),
63  z_scale_(1.0), x_scale_(3.5),
64  z_tol_(0.1), x_tol_(0.1),
65  enabled_(true)
66  {
67 
68  }
69 
71  {
72  delete config_srv_;
73  }
74 
75 private:
76  double min_y_;
77  double max_y_;
78  double min_x_;
79  double max_x_;
80  double max_z_;
81  double goal_z_;
82  double z_scale_;
83  double x_scale_;
84  double z_tol_;
85  double x_tol_;
86  bool enabled_;
88  // Service for start/stop following
89  // ros::ServiceServer switch_srv_;
90 
91  // Dynamic reconfigure server
92  dynamic_reconfigure::Server<oculusprime::FollowerConfig>* config_srv_;
93 
99  virtual void onInit()
100  {
102  ros::NodeHandle& private_nh = getPrivateNodeHandle();
103 
104  private_nh.getParam("min_y", min_y_);
105  private_nh.getParam("max_y", max_y_);
106  private_nh.getParam("min_x", min_x_);
107  private_nh.getParam("max_x", max_x_);
108  private_nh.getParam("max_z", max_z_);
109  private_nh.getParam("goal_z", goal_z_);
110  private_nh.getParam("z_scale", z_scale_);
111  private_nh.getParam("x_scale", x_scale_);
112  private_nh.getParam("z_tol", z_tol_);
113  private_nh.getParam("x_tol", x_tol_);
114  private_nh.getParam("enabled", enabled_);
115 
116  cmdpub_ = nh.advertise<geometry_msgs::Twist> ("/cmd_vel", 1);
117  markerpub_ = nh.advertise<visualization_msgs::Marker>("marker",1);
118  bboxpub_ = private_nh.advertise<visualization_msgs::Marker>("bbox",1);
119  sub_= nh.subscribe<PointCloud>("depth/points", 1, &OculusprimeFollower::cloudcb, this);
120 
121  // switch_srv_ = private_nh.advertiseService("change_state", &OculusprimeFollower::changeModeSrvCb, this);
122 
123  config_srv_ = new dynamic_reconfigure::Server<oculusprime::FollowerConfig>(private_nh);
124  dynamic_reconfigure::Server<oculusprime::FollowerConfig>::CallbackType f =
125  boost::bind(&OculusprimeFollower::reconfigure, this, _1, _2);
126  config_srv_->setCallback(f);
127 
128  ROS_INFO("OculusprimeFollower init");
129  }
130 
131  void reconfigure(oculusprime::FollowerConfig &config, uint32_t level)
132  {
133  min_y_ = config.min_y;
134  max_y_ = config.max_y;
135  min_x_ = config.min_x;
136  max_x_ = config.max_x;
137  max_z_ = config.max_z;
138  goal_z_ = config.goal_z;
139  z_scale_ = config.z_scale;
140  x_scale_ = config.x_scale;
141  z_tol_ = config.z_tol;
142  x_tol_ = config.x_tol;
143  enabled_ = config.enabled;
144  }
145 
153  void cloudcb(const PointCloud::ConstPtr& cloud)
154  {
155  //X,Y,Z of the centroid
156  float x = 0.0;
157  float y = 0.0;
158  float z = 1e6;
159  //Number of points observed
160  unsigned int n = 0;
161  //Iterate through all the points in the region and find the average of the position
162  BOOST_FOREACH (const pcl::PointXYZ& pt, cloud->points)
163  {
164  //First, ensure that the point's position is valid. This must be done in a seperate
165  //if because we do not want to perform comparison on a nan value.
166  if (!std::isnan(x) && !std::isnan(y) && !std::isnan(z))
167  {
168  //Test to ensure the point is within the aceptable box.
169  if (-pt.y > min_y_ && -pt.y < max_y_ && pt.x < max_x_ && pt.x > min_x_ && pt.z < max_z_)
170  {
171  //Add the point to the totals
172  x += pt.x;
173  y += pt.y;
174  z = std::min(z, pt.z);
175  n++;
176  }
177  }
178  }
179 
180  //If there are points, find the centroid and calculate the command goal.
181  //If there are no points, simply publish a stop goal.
182  if (n>4000)
183  {
184  x /= n;
185  y /= n;
186  if(z > max_z_){
187  ROS_DEBUG("No valid points detected, stopping the robot");
188  if (enabled_)
189  {
190  cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
191  }
192  return;
193  }
194 
195  ROS_DEBUG("Centroid at %f %f %f with %d points", x, y, z, n);
196  publishMarker(x, y, z);
197 
198  if (enabled_)
199  {
200  geometry_msgs::TwistPtr cmd(new geometry_msgs::Twist());
201 
202  if ( std::abs(z-goal_z_)<z_tol_) { cmd->linear.x = 0; }
203  else { cmd->linear.x = (z - goal_z_) * z_scale_; }
204 
205  if (std::abs(x) < x_tol_) { cmd->angular.z = 0; } // avoid backwards arc-turns
206  else { cmd->angular.z = -x * x_scale_; }
207 
208  cmdpub_.publish(cmd);
209  }
210  }
211  else
212  {
213  ROS_DEBUG("No points detected, stopping the robot, # points= %d", n);
214  publishMarker(x, y, z);
215 
216  if (enabled_)
217  {
218  cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
219  }
220  }
221 
222  publishBbox();
223  }
224 
225 /*
226  bool changeModeSrvCb(turtlebot_msgs::SetFollowState::Request& request,
227  turtlebot_msgs::SetFollowState::Response& response)
228  {
229  if ((enabled_ == true) && (request.state == request.STOPPED))
230  {
231  ROS_INFO("Change mode service request: following stopped");
232  cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
233  enabled_ = false;
234  }
235  else if ((enabled_ == false) && (request.state == request.FOLLOW))
236  {
237  ROS_INFO("Change mode service request: following (re)started");
238  enabled_ = true;
239  }
240 
241  response.result = response.OK;
242  return true;
243  }
244 */
245 
246  void publishMarker(double x,double y,double z)
247  {
248  visualization_msgs::Marker marker;
249  marker.header.frame_id = "/camera_rgb_optical_frame";
250  marker.header.stamp = ros::Time();
251  marker.ns = "my_namespace";
252  marker.id = 0;
253  marker.type = visualization_msgs::Marker::SPHERE;
254  marker.action = visualization_msgs::Marker::ADD;
255  marker.pose.position.x = x;
256  marker.pose.position.y = y;
257  marker.pose.position.z = z;
258  marker.pose.orientation.x = 0.0;
259  marker.pose.orientation.y = 0.0;
260  marker.pose.orientation.z = 0.0;
261  marker.pose.orientation.w = 1.0;
262  marker.scale.x = 0.2;
263  marker.scale.y = 0.2;
264  marker.scale.z = 0.2;
265  marker.color.a = 1.0;
266  marker.color.r = 1.0;
267  marker.color.g = 0.0;
268  marker.color.b = 0.0;
269  //only if using a MESH_RESOURCE marker type:
270  markerpub_.publish( marker );
271  }
272 
273  void publishBbox()
274  {
275  double x = (min_x_ + max_x_)/2;
276  double y = (min_y_ + max_y_)/2;
277  double z = (0 + max_z_)/2;
278 
279  double scale_x = (max_x_ - x)*2;
280  double scale_y = (max_y_ - y)*2;
281  double scale_z = (max_z_ - z)*2;
282 
283  visualization_msgs::Marker marker;
284  marker.header.frame_id = "/camera_rgb_optical_frame";
285  marker.header.stamp = ros::Time();
286  marker.ns = "my_namespace";
287  marker.id = 1;
288  marker.type = visualization_msgs::Marker::CUBE;
289  marker.action = visualization_msgs::Marker::ADD;
290  marker.pose.position.x = x;
291  marker.pose.position.y = -y;
292  marker.pose.position.z = z;
293  marker.pose.orientation.x = 0.0;
294  marker.pose.orientation.y = 0.0;
295  marker.pose.orientation.z = 0.0;
296  marker.pose.orientation.w = 1.0;
297  marker.scale.x = scale_x;
298  marker.scale.y = scale_y;
299  marker.scale.z = scale_z;
300  marker.color.a = 0.5;
301  marker.color.r = 0.0;
302  marker.color.g = 1.0;
303  marker.color.b = 0.0;
304  //only if using a MESH_RESOURCE marker type:
305  bboxpub_.publish( marker );
306  }
307 
312 };
313 
315 
316 }
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
string cmd
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
TFSIMD_FORCE_INLINE const tfScalar & y() const
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: follower.cpp:45
ros::NodeHandle & getPrivateNodeHandle() const
OculusprimeFollower()
The constructor for the follower. Constructor for the follower.
Definition: follower.cpp:60
dynamic_reconfigure::Server< oculusprime::FollowerConfig > * config_srv_
Definition: follower.cpp:92
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void cloudcb(const PointCloud::ConstPtr &cloud)
Callback for point clouds. Callback for point clouds. Uses PCL to find the centroid of the points in ...
Definition: follower.cpp:153
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
void publishMarker(double x, double y, double z)
Definition: follower.cpp:246
bool getParam(const std::string &key, std::string &s) const
void reconfigure(oculusprime::FollowerConfig &config, uint32_t level)
Definition: follower.cpp:131
#define n
virtual void onInit()
OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics...
Definition: follower.cpp:99
#define ROS_DEBUG(...)


oculusprime
Author(s): Colin Adamson
autogenerated on Wed Mar 10 2021 03:14:59