33 #include <geometry_msgs/Twist.h> 35 #include <pcl/point_types.h> 36 #include <visualization_msgs/Marker.h> 39 #include "dynamic_reconfigure/server.h" 40 #include "oculusprime/FollowerConfig.h" 92 dynamic_reconfigure::Server<oculusprime::FollowerConfig>*
config_srv_;
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_);
123 config_srv_ =
new dynamic_reconfigure::Server<oculusprime::FollowerConfig>(private_nh);
124 dynamic_reconfigure::Server<oculusprime::FollowerConfig>::CallbackType
f =
126 config_srv_->setCallback(f);
128 ROS_INFO(
"OculusprimeFollower init");
131 void reconfigure(oculusprime::FollowerConfig &config, uint32_t level)
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;
153 void cloudcb(
const PointCloud::ConstPtr& cloud)
162 BOOST_FOREACH (
const pcl::PointXYZ& pt, cloud->points)
166 if (!std::isnan(x) && !std::isnan(y) && !std::isnan(z))
169 if (-pt.y > min_y_ && -pt.y < max_y_ && pt.x < max_x_ && pt.x > min_x_ && pt.z < max_z_)
174 z = std::min(z, pt.z);
187 ROS_DEBUG(
"No valid points detected, stopping the robot");
190 cmdpub_.
publish(geometry_msgs::TwistPtr(
new geometry_msgs::Twist()));
195 ROS_DEBUG(
"Centroid at %f %f %f with %d points", x, y, z, n);
200 geometry_msgs::TwistPtr
cmd(
new geometry_msgs::Twist());
202 if ( std::abs(z-goal_z_)<z_tol_) { cmd->linear.x = 0; }
203 else { cmd->linear.x = (z -
goal_z_) * z_scale_; }
205 if (std::abs(x) <
x_tol_) { cmd->angular.z = 0; }
206 else { cmd->angular.z = -x *
x_scale_; }
213 ROS_DEBUG(
"No points detected, stopping the robot, # points= %d", n);
218 cmdpub_.
publish(geometry_msgs::TwistPtr(
new geometry_msgs::Twist()));
248 visualization_msgs::Marker marker;
249 marker.header.frame_id =
"/camera_rgb_optical_frame";
251 marker.ns =
"my_namespace";
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;
275 double x = (min_x_ +
max_x_)/2;
276 double y = (min_y_ +
max_y_)/2;
279 double scale_x = (max_x_ - x)*2;
280 double scale_y = (max_y_ - y)*2;
281 double scale_z = (max_z_ - z)*2;
283 visualization_msgs::Marker marker;
284 marker.header.frame_id =
"/camera_rgb_optical_frame";
286 marker.ns =
"my_namespace";
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;
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())
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
ros::Publisher markerpub_
TFSIMD_FORCE_INLINE const tfScalar & y() const
pcl::PointCloud< pcl::PointXYZ > PointCloud
ros::NodeHandle & getPrivateNodeHandle() const
OculusprimeFollower()
The constructor for the follower. Constructor for the follower.
dynamic_reconfigure::Server< oculusprime::FollowerConfig > * config_srv_
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 ...
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)
bool getParam(const std::string &key, std::string &s) const
void reconfigure(oculusprime::FollowerConfig &config, uint32_t level)
virtual void onInit()
OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics...