33 #include <geometry_msgs/Twist.h>    34 #include <sensor_msgs/Image.h>    35 #include <visualization_msgs/Marker.h>    36 #include <turtlebot_msgs/SetFollowState.h>    38 #include "dynamic_reconfigure/server.h"    39 #include "turtlebot_follower/FollowerConfig.h"    88   dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>* 
config_srv_;
   100     private_nh.
getParam(
"min_y", min_y_);
   101     private_nh.
getParam(
"max_y", max_y_);
   102     private_nh.
getParam(
"min_x", min_x_);
   103     private_nh.
getParam(
"max_x", max_x_);
   104     private_nh.
getParam(
"max_z", max_z_);
   105     private_nh.
getParam(
"goal_z", goal_z_);
   106     private_nh.
getParam(
"z_scale", z_scale_);
   107     private_nh.
getParam(
"x_scale", x_scale_);
   108     private_nh.
getParam(
"enabled", enabled_);
   117     config_srv_ = 
new dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>(private_nh);
   118     dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>::CallbackType 
f =
   120     config_srv_->setCallback(f);
   125     min_y_ = config.min_y;
   126     max_y_ = config.max_y;
   127     min_x_ = config.min_x;
   128     max_x_ = config.max_x;
   129     max_z_ = config.max_z;
   130     goal_z_ = config.goal_z;
   131     z_scale_ = config.z_scale;
   132     x_scale_ = config.x_scale;
   142   void imagecb(
const sensor_msgs::ImageConstPtr& depth_msg)
   146     uint32_t image_width = depth_msg->width;
   147     float x_radians_per_pixel = 60.0/57.0/image_width;
   148     float sin_pixel_x[image_width];
   149     for (
int x = 0; 
x < image_width; ++
x) {
   150       sin_pixel_x[
x] = 
sin((
x - image_width/ 2.0)  * x_radians_per_pixel);
   153     uint32_t image_height = depth_msg->height;
   154     float y_radians_per_pixel = 45.0/57.0/image_width;
   155     float sin_pixel_y[image_height];
   156     for (
int y = 0; 
y < image_height; ++
y) {
   158       sin_pixel_y[
y] = 
sin((image_height/ 2.0 - 
y)  * y_radians_per_pixel);
   169     const float* depth_row = 
reinterpret_cast<const float*
>(&depth_msg->data[0]);
   170     int row_step = depth_msg->step / 
sizeof(float);
   171     for (
int v = 0; 
v < (
int)depth_msg->height; ++
v, depth_row += row_step)
   173      for (
int u = 0; u < (
int)depth_msg->width; ++u)
   177        float y_val = sin_pixel_y[
v] * depth;
   178        float x_val = sin_pixel_x[u] * depth;
   179        if ( y_val > min_y_ && y_val < max_y_ &&
   180             x_val > min_x_ && x_val < max_x_)
   184          z = std::min(z, depth); 
   200           cmdpub_.
publish(geometry_msgs::TwistPtr(
new geometry_msgs::Twist()));
   210         geometry_msgs::TwistPtr 
cmd(
new geometry_msgs::Twist());
   211         cmd->linear.x = (z - 
goal_z_) * z_scale_;
   223         cmdpub_.
publish(geometry_msgs::TwistPtr(
new geometry_msgs::Twist()));
   231                        turtlebot_msgs::SetFollowState::Response& response)
   233     if ((enabled_ == 
true) && (request.state == request.STOPPED))
   235       ROS_INFO(
"Change mode service request: following stopped");
   236       cmdpub_.
publish(geometry_msgs::TwistPtr(
new geometry_msgs::Twist()));
   239     else if ((enabled_ == 
false) && (request.state == request.FOLLOW))
   241       ROS_INFO(
"Change mode service request: following (re)started");
   245     response.result = response.OK;
   251     visualization_msgs::Marker 
marker;
   252     marker.header.frame_id = 
"/camera_rgb_optical_frame";
   254     marker.ns = 
"my_namespace";
   256     marker.type = visualization_msgs::Marker::SPHERE;
   257     marker.action = visualization_msgs::Marker::ADD;
   258     marker.pose.position.x = x;
   259     marker.pose.position.y = y;
   260     marker.pose.position.z = z;
   261     marker.pose.orientation.x = 0.0;
   262     marker.pose.orientation.y = 0.0;
   263     marker.pose.orientation.z = 0.0;
   264     marker.pose.orientation.w = 1.0;
   265     marker.scale.x = 0.2;
   266     marker.scale.y = 0.2;
   267     marker.scale.z = 0.2;
   268     marker.color.a = 1.0;
   269     marker.color.r = 1.0;
   270     marker.color.g = 0.0;
   271     marker.color.b = 0.0;
   278     double x = (min_x_ + 
max_x_)/2;
   279     double y = (min_y_ + 
max_y_)/2;
   282     double scale_x = (max_x_ - x)*2;
   283     double scale_y = (max_y_ - y)*2;
   284     double scale_z = (max_z_ - z)*2;
   286     visualization_msgs::Marker 
marker;
   287     marker.header.frame_id = 
"/camera_rgb_optical_frame";
   289     marker.ns = 
"my_namespace";
   291     marker.type = visualization_msgs::Marker::CUBE;
   292     marker.action = visualization_msgs::Marker::ADD;
   293     marker.pose.position.x = x;
   294     marker.pose.position.y = -y;
   295     marker.pose.position.z = z;
   296     marker.pose.orientation.x = 0.0;
   297     marker.pose.orientation.y = 0.0;
   298     marker.pose.orientation.z = 0.0;
   299     marker.pose.orientation.w = 1.0;
   300     marker.scale.x = scale_x;
   301     marker.scale.y = scale_y;
   302     marker.scale.z = scale_z;
   303     marker.color.a = 0.5;
   304     marker.color.r = 0.0;
   305     marker.color.g = 1.0;
   306     marker.color.b = 0.0;
 
virtual void onInit()
OnInit method from node handle. OnInit method from node handle. Sets up the parameters and topics...
 
TurtlebotFollower()
The constructor for the follower. Constructor for the follower. 
 
void imagecb(const sensor_msgs::ImageConstPtr &depth_msg)
Callback for point clouds. Callback for depth images. It finds the centroid of the points in a box in...
 
void publish(const boost::shared_ptr< M > &message) const 
 
dynamic_reconfigure::Server< turtlebot_follower::FollowerConfig > * config_srv_
 
GLint GLint GLint GLint GLint GLint y
 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
 
void reconfigure(turtlebot_follower::FollowerConfig &config, uint32_t level)
 
ros::Publisher markerpub_
 
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
 
GLint GLint GLsizei GLsizei GLsizei depth
 
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
ros::NodeHandle & getPrivateNodeHandle() const 
 
ros::ServiceServer switch_srv_
 
void publishMarker(double x, double y, double z)
 
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
 
ros::NodeHandle & getNodeHandle() const 
 
bool getParam(const std::string &key, std::string &s) const 
 
#define ROS_INFO_THROTTLE(rate,...)
 
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
 
GLint GLint GLint GLint GLint x
 
bool changeModeSrvCb(turtlebot_msgs::SetFollowState::Request &request, turtlebot_msgs::SetFollowState::Response &response)