cam3d_throttle.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
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 //typedef message_filters::sync_policies::ApproximateTime<tPointCloud, tImage, tCameraInfo, tImage, tPointCloud> tSyncPolicy;
00037 typedef message_filters::sync_policies::ApproximateTime<tPointCloud, tImage, tCameraInfo> tSyncPolicy;
00038 
00039 class Cam3DThrottle : public nodelet::Nodelet
00040 {
00041 public:
00042   //Constructor
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     //sync_.connectInput(rgb_cloud_sub_, rgb_image_sub_, rgb_caminfo_sub_, depth_image_sub_, cloud_sub_);
00066     //sync_.registerCallback(boost::bind(&Cam3DThrottle::callback, this, _1, _2, _3, _4, _5));
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 /*  void callback(const tPointCloud::ConstPtr& rgb_cloud,
00072                 const tImage::ConstPtr& rgb_image,
00073                 const tCameraInfo::ConstPtr& rgb_caminfo,
00074                 const tImage::ConstPtr& depth_image,
00075                 const tPointCloud::ConstPtr& cloud
00076                 )
00077   {
00078     if (max_update_rate_ > 0.0)
00079     {
00080       NODELET_DEBUG("update set to %f", max_update_rate_);
00081       if ( last_update_ + ros::Duration(1.0/max_update_rate_) > ros::Time::now())
00082       {
00083         NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
00084         return;
00085       }
00086     }
00087     else
00088       NODELET_DEBUG("update_rate unset continuing");
00089     last_update_ = ros::Time::now();
00090     rgb_cloud_pub_.publish(rgb_cloud);
00091     rgb_image_pub_.publish(rgb_image);
00092     rgb_caminfo_pub_.publish(rgb_caminfo);
00093     depth_image_pub_.publish(depth_image);
00094     cloud_pub_.publish(cloud);
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       //std::cout << "update rate: " << max_update_rate_ << std::endl;
00107       if ( last_update_ + ros::Duration(1.0/max_update_rate_) > ros::Time::now())
00108       {
00109         //std::cout << "last_update[s] " << last_update_.toSec() << std::endl;
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     //std::cout << "publishing" << std::endl;
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     //std::cout << "connectCB: "<<  sub_counter_ << std::endl;
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 //      depth_image_sub_.subscribe(nh_, "depth_image_in", 1);
00136 //      cloud_sub_.subscribe(nh_, "cloud_in", 1);
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 //      depth_image_sub_.unsubscribe();
00150 //      cloud_sub_.unsubscribe();
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 


cob_cam3d_throttle
Author(s): Georg Arbeiter
autogenerated on Fri Mar 15 2019 03:10:02