00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include "ros/ros.h"
00019 #include "pluginlib/class_list_macros.h"
00020 #include "nodelet/nodelet.h"
00021
00022 #include "sensor_msgs/PointCloud2.h"
00023 #include <sensor_msgs/Image.h>
00024 #include <sensor_msgs/CameraInfo.h>
00025
00026 #include <message_filters/subscriber.h>
00027 #include <message_filters/synchronizer.h>
00028 #include <message_filters/sync_policies/approximate_time.h>
00029
00030
00031 namespace cob_cam3d_throttle
00032 {
00033 typedef sensor_msgs::PointCloud2 tPointCloud;
00034 typedef sensor_msgs::Image tImage;
00035 typedef sensor_msgs::CameraInfo tCameraInfo;
00036
00037 typedef message_filters::sync_policies::ApproximateTime<tPointCloud, tImage, tCameraInfo> tSyncPolicy;
00038
00039 class Cam3DThrottle : public nodelet::Nodelet
00040 {
00041 public:
00042
00043 Cam3DThrottle() :
00044 max_update_rate_(0),
00045 sub_counter_(0),
00046 sync_(tSyncPolicy(3))
00047 {
00048 };
00049
00050 private:
00051 virtual void onInit()
00052 {
00053 nh_ = getNodeHandle();
00054 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00055
00056 private_nh.getParam("max_rate", max_update_rate_);
00057
00058 rgb_cloud_pub_ = nh_.advertise<tPointCloud>("rgb_cloud_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
00059 rgb_image_pub_ = nh_.advertise<tImage>("rgb_image_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
00060 rgb_caminfo_pub_ = nh_.advertise<tCameraInfo>("rgb_caminfo_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
00061 depth_image_pub_ = nh_.advertise<tImage>("depth_image_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
00062 cloud_pub_ = nh_.advertise<tPointCloud>("cloud_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
00063
00064 last_update_ = ros::Time::now();
00065
00066
00067 sync_.connectInput(rgb_cloud_sub_, rgb_image_sub_, rgb_caminfo_sub_);
00068 sync_.registerCallback(boost::bind(&Cam3DThrottle::callback, this, _1, _2, _3));
00069 };
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097 void callback(const tPointCloud::ConstPtr& rgb_cloud,
00098 const tImage::ConstPtr& rgb_image,
00099 const tCameraInfo::ConstPtr& rgb_caminfo
00100 )
00101 {
00102
00103 if (max_update_rate_ > 0.0)
00104 {
00105 NODELET_DEBUG("update set to %f", max_update_rate_);
00106
00107 if ( last_update_ + ros::Duration(1.0/max_update_rate_) > ros::Time::now())
00108 {
00109
00110 NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
00111 return;
00112 }
00113 }
00114 else
00115 {
00116 NODELET_DEBUG("update_rate unset continuing");
00117 }
00118
00119 last_update_ = ros::Time::now();
00120 rgb_cloud_pub_.publish(rgb_cloud);
00121 rgb_image_pub_.publish(rgb_image);
00122 rgb_caminfo_pub_.publish(rgb_caminfo);
00123 }
00124
00125 void connectCB(const ros::SingleSubscriberPublisher& pub)
00126 {
00127 sub_counter_++;
00128
00129 if(sub_counter_ == 1)
00130 {
00131 ROS_DEBUG("connecting");
00132 rgb_cloud_sub_.subscribe(nh_, "rgb_cloud_in", 1);
00133 rgb_image_sub_.subscribe(nh_, "rgb_image_in", 1);
00134 rgb_caminfo_sub_.subscribe(nh_, "rgb_caminfo_in", 1);
00135
00136
00137 }
00138 }
00139
00140 void disconnectCB(const ros::SingleSubscriberPublisher& pub)
00141 {
00142 sub_counter_--;
00143 if(sub_counter_ == 0)
00144 {
00145 ROS_DEBUG("disconnecting");
00146 rgb_cloud_sub_.unsubscribe();
00147 rgb_image_sub_.unsubscribe();
00148 rgb_caminfo_sub_.unsubscribe();
00149
00150
00151 }
00152 }
00153
00154 ros::Time last_update_;
00155 double max_update_rate_;
00156 unsigned int sub_counter_;
00157
00158 ros::NodeHandle nh_;
00159 ros::Subscriber sub_;
00160 ros::Subscriber sub2_;
00161 ros::Publisher rgb_cloud_pub_, rgb_image_pub_, rgb_caminfo_pub_, depth_image_pub_, cloud_pub_;
00162
00163 message_filters::Subscriber<tPointCloud> rgb_cloud_sub_;
00164 message_filters::Subscriber<tImage> rgb_image_sub_;
00165 message_filters::Subscriber<tCameraInfo> rgb_caminfo_sub_;
00166 message_filters::Subscriber<tImage> depth_image_sub_;
00167 message_filters::Subscriber<tPointCloud> cloud_sub_;
00168 message_filters::Synchronizer<tSyncPolicy> sync_;
00169
00170 };
00171
00172
00173 PLUGINLIB_EXPORT_CLASS(cob_cam3d_throttle::Cam3DThrottle, nodelet::Nodelet);
00174 }
00175