cam3d_throttle.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include "ros/ros.h"
20 #include "nodelet/nodelet.h"
21 
22 #include "sensor_msgs/PointCloud2.h"
23 #include <sensor_msgs/Image.h>
24 #include <sensor_msgs/CameraInfo.h>
25 
29 
30 
32 {
33 typedef sensor_msgs::PointCloud2 tPointCloud;
34 typedef sensor_msgs::Image tImage;
35 typedef sensor_msgs::CameraInfo tCameraInfo;
36 //typedef message_filters::sync_policies::ApproximateTime<tPointCloud, tImage, tCameraInfo, tImage, tPointCloud> tSyncPolicy;
38 
40 {
41 public:
42  //Constructor
45  sub_counter_(0),
46  sync_(tSyncPolicy(3))
47  {
48  };
49 
50 private:
51  virtual void onInit()
52  {
53  nh_ = getNodeHandle();
54  ros::NodeHandle& private_nh = getPrivateNodeHandle();
55 
56  private_nh.getParam("max_rate", max_update_rate_);
57 
58  rgb_cloud_pub_ = nh_.advertise<tPointCloud>("rgb_cloud_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
59  rgb_image_pub_ = nh_.advertise<tImage>("rgb_image_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
60  rgb_caminfo_pub_ = nh_.advertise<tCameraInfo>("rgb_caminfo_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
61  depth_image_pub_ = nh_.advertise<tImage>("depth_image_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
62  cloud_pub_ = nh_.advertise<tPointCloud>("cloud_out", 1, boost::bind(&Cam3DThrottle::connectCB, this, _1), boost::bind(&Cam3DThrottle::disconnectCB, this, _1));
63 
65  //sync_.connectInput(rgb_cloud_sub_, rgb_image_sub_, rgb_caminfo_sub_, depth_image_sub_, cloud_sub_);
66  //sync_.registerCallback(boost::bind(&Cam3DThrottle::callback, this, _1, _2, _3, _4, _5));
68  sync_.registerCallback(boost::bind(&Cam3DThrottle::callback, this, _1, _2, _3));
69  };
70 
71 /* void callback(const tPointCloud::ConstPtr& rgb_cloud,
72  const tImage::ConstPtr& rgb_image,
73  const tCameraInfo::ConstPtr& rgb_caminfo,
74  const tImage::ConstPtr& depth_image,
75  const tPointCloud::ConstPtr& cloud
76  )
77  {
78  if (max_update_rate_ > 0.0)
79  {
80  NODELET_DEBUG("update set to %f", max_update_rate_);
81  if ( last_update_ + ros::Duration(1.0/max_update_rate_) > ros::Time::now())
82  {
83  NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
84  return;
85  }
86  }
87  else
88  NODELET_DEBUG("update_rate unset continuing");
89  last_update_ = ros::Time::now();
90  rgb_cloud_pub_.publish(rgb_cloud);
91  rgb_image_pub_.publish(rgb_image);
92  rgb_caminfo_pub_.publish(rgb_caminfo);
93  depth_image_pub_.publish(depth_image);
94  cloud_pub_.publish(cloud);
95  }*/
96 
97  void callback(const tPointCloud::ConstPtr& rgb_cloud,
98  const tImage::ConstPtr& rgb_image,
99  const tCameraInfo::ConstPtr& rgb_caminfo
100  )
101  {
102 
103  if (max_update_rate_ > 0.0)
104  {
105  NODELET_DEBUG("update set to %f", max_update_rate_);
106  //std::cout << "update rate: " << max_update_rate_ << std::endl;
108  {
109  //std::cout << "last_update[s] " << last_update_.toSec() << std::endl;
110  NODELET_DEBUG("throttle last update at %f skipping", last_update_.toSec());
111  return;
112  }
113  }
114  else
115  {
116  NODELET_DEBUG("update_rate unset continuing");
117  }
118  //std::cout << "publishing" << std::endl;
120  rgb_cloud_pub_.publish(rgb_cloud);
121  rgb_image_pub_.publish(rgb_image);
122  rgb_caminfo_pub_.publish(rgb_caminfo);
123  }
124 
126  {
127  sub_counter_++;
128  //std::cout << "connectCB: "<< sub_counter_ << std::endl;
129  if(sub_counter_ == 1)
130  {
131  ROS_DEBUG("connecting");
132  rgb_cloud_sub_.subscribe(nh_, "rgb_cloud_in", 1);
133  rgb_image_sub_.subscribe(nh_, "rgb_image_in", 1);
134  rgb_caminfo_sub_.subscribe(nh_, "rgb_caminfo_in", 1);
135 // depth_image_sub_.subscribe(nh_, "depth_image_in", 1);
136 // cloud_sub_.subscribe(nh_, "cloud_in", 1);
137  }
138  }
139 
141  {
142  sub_counter_--;
143  if(sub_counter_ == 0)
144  {
145  ROS_DEBUG("disconnecting");
149 // depth_image_sub_.unsubscribe();
150 // cloud_sub_.unsubscribe();
151  }
152  }
153 
156  unsigned int sub_counter_;
157 
162 
169 
170 };
171 
172 
174 }
175 
cob_cam3d_throttle::Cam3DThrottle::onInit
virtual void onInit()
Definition: cam3d_throttle.cpp:51
cob_cam3d_throttle::Cam3DThrottle::rgb_caminfo_sub_
message_filters::Subscriber< tCameraInfo > rgb_caminfo_sub_
Definition: cam3d_throttle.cpp:165
cob_cam3d_throttle::Cam3DThrottle::sub2_
ros::Subscriber sub2_
Definition: cam3d_throttle.cpp:160
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
cob_cam3d_throttle::Cam3DThrottle::depth_image_sub_
message_filters::Subscriber< tImage > depth_image_sub_
Definition: cam3d_throttle.cpp:166
message_filters::Synchronizer
cob_cam3d_throttle::Cam3DThrottle::depth_image_pub_
ros::Publisher depth_image_pub_
Definition: cam3d_throttle.cpp:161
cob_cam3d_throttle::tCameraInfo
sensor_msgs::CameraInfo tCameraInfo
Definition: cam3d_throttle.cpp:35
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
cob_cam3d_throttle
Definition: cam3d_throttle.cpp:31
cob_cam3d_throttle::Cam3DThrottle::sync_
message_filters::Synchronizer< tSyncPolicy > sync_
Definition: cam3d_throttle.cpp:168
cob_cam3d_throttle::Cam3DThrottle
Definition: cam3d_throttle.cpp:39
cob_cam3d_throttle::Cam3DThrottle::rgb_caminfo_pub_
ros::Publisher rgb_caminfo_pub_
Definition: cam3d_throttle.cpp:161
TimeBase< Time, Duration >::toSec
double toSec() const
cob_cam3d_throttle::Cam3DThrottle::sub_
ros::Subscriber sub_
Definition: cam3d_throttle.cpp:159
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
message_filters::Subscriber< tPointCloud >
cob_cam3d_throttle::tSyncPolicy
message_filters::sync_policies::ApproximateTime< tPointCloud, tImage, tCameraInfo > tSyncPolicy
Definition: cam3d_throttle.cpp:37
class_list_macros.h
ros::SingleSubscriberPublisher
message_filters::sync_policies::ApproximateTime
cob_cam3d_throttle::Cam3DThrottle::max_update_rate_
double max_update_rate_
Definition: cam3d_throttle.cpp:155
ROS_DEBUG
#define ROS_DEBUG(...)
subscriber.h
cob_cam3d_throttle::Cam3DThrottle::connectCB
void connectCB(const ros::SingleSubscriberPublisher &pub)
Definition: cam3d_throttle.cpp:125
cob_cam3d_throttle::Cam3DThrottle::nh_
ros::NodeHandle nh_
Definition: cam3d_throttle.cpp:158
cob_cam3d_throttle::Cam3DThrottle::rgb_cloud_sub_
message_filters::Subscriber< tPointCloud > rgb_cloud_sub_
Definition: cam3d_throttle.cpp:163
cob_cam3d_throttle::Cam3DThrottle::Cam3DThrottle
Cam3DThrottle()
Definition: cam3d_throttle.cpp:43
cob_cam3d_throttle::Cam3DThrottle::cloud_sub_
message_filters::Subscriber< tPointCloud > cloud_sub_
Definition: cam3d_throttle.cpp:167
cob_cam3d_throttle::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(cob_cam3d_throttle::Cam3DThrottle, nodelet::Nodelet)
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
ros::Time
cob_cam3d_throttle::tPointCloud
sensor_msgs::PointCloud2 tPointCloud
Definition: cam3d_throttle.cpp:33
nodelet.h
cob_cam3d_throttle::Cam3DThrottle::disconnectCB
void disconnectCB(const ros::SingleSubscriberPublisher &pub)
Definition: cam3d_throttle.cpp:140
cob_cam3d_throttle::Cam3DThrottle::last_update_
ros::Time last_update_
Definition: cam3d_throttle.cpp:154
cob_cam3d_throttle::Cam3DThrottle::sub_counter_
unsigned int sub_counter_
Definition: cam3d_throttle.cpp:156
synchronizer.h
cob_cam3d_throttle::Cam3DThrottle::callback
void callback(const tPointCloud::ConstPtr &rgb_cloud, const tImage::ConstPtr &rgb_image, const tCameraInfo::ConstPtr &rgb_caminfo)
Definition: cam3d_throttle.cpp:97
approximate_time.h
cob_cam3d_throttle::Cam3DThrottle::cloud_pub_
ros::Publisher cloud_pub_
Definition: cam3d_throttle.cpp:161
cob_cam3d_throttle::Cam3DThrottle::rgb_image_sub_
message_filters::Subscriber< tImage > rgb_image_sub_
Definition: cam3d_throttle.cpp:164
cob_cam3d_throttle::Cam3DThrottle::rgb_image_pub_
ros::Publisher rgb_image_pub_
Definition: cam3d_throttle.cpp:161
cob_cam3d_throttle::Cam3DThrottle::rgb_cloud_pub_
ros::Publisher rgb_cloud_pub_
Definition: cam3d_throttle.cpp:161
cob_cam3d_throttle::tImage
sensor_msgs::Image tImage
Definition: cam3d_throttle.cpp:34
ros::Duration
ros::NodeHandle
ros::Subscriber
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()


cob_cam3d_throttle
Author(s): Georg Arbeiter
autogenerated on Thu Feb 22 2024 03:28:37