visionary_t_mini.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2023 SICK AG, Waldkirch
3 //
4 // SPDX-License-Identifier: Unlicense
5 
6 #include <boost/thread.hpp>
7 #include <cv_bridge/cv_bridge.h>
9 #include <ros/ros.h>
10 #include <sensor_msgs/CameraInfo.h>
11 #include <sensor_msgs/LaserScan.h>
12 #include <sensor_msgs/PointCloud2.h>
14 #include <std_msgs/ByteMultiArray.h>
15 #include <memory>
16 
19 
20 #include "VisionaryControl.h"
21 #include "VisionaryDataStream.h"
22 #include "VisionaryTMiniData.h" // Header specific for the Time of Flight data
23 
24 using namespace visionary;
25 
26 std::shared_ptr<VisionaryControl> gControl;
27 
28 std::shared_ptr<VisionaryTMiniData> gDataHandler;
29 
32 
33 std::shared_ptr<diagnostic_updater::Updater> updater;
34 std::shared_ptr<diagnostic_updater::TopicDiagnostic> gPubDepth_freq, gPubIntensity_freq, gPubStatemap_freq;
35 std::shared_ptr<diagnostic_updater::TopicDiagnostic> gPubCameraInfo_freq, gPubPoints_freq;
36 
37 std::string gFrameId;
38 std::string gDeviceIdent;
40 
41 boost::mutex gDataMtx;
42 bool gReceive = true;
43 
44 int gNumSubs = 0;
45 
47 {
48  updater->update();
49 }
50 
52 {
53  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "driver running");
54  stat.add("frame_id", gFrameId);
55  stat.add("device_ident", gDeviceIdent);
56  stat.add("NumSubscribers_CameraInfo", gPubCameraInfo.getNumSubscribers());
57  stat.add("gEnablePoints", gEnablePoints);
58  if (gEnablePoints)
59  stat.add("NumSubscribers_Points", gPubPoints.getNumSubscribers());
60  stat.add("gEnableDepth", gEnableDepth);
61  if (gEnableDepth)
62  stat.add("NumSubscribers_Depth", gPubDepth.getNumSubscribers());
63  stat.add("gEnableIntensity", gEnableIntensity);
64  if (gEnableIntensity)
65  stat.add("NumSubscribers_Intensity", gPubIntensity.getNumSubscribers());
66  stat.add("gEnableStatemap", gEnableStatemap);
67  if (gEnableStatemap)
68  stat.add("NumSubscribers_Statemap", gPubStatemap.getNumSubscribers());
69 }
70 
71 void publishCameraInfo(std_msgs::Header header, VisionaryTMiniData& dataHandler)
72 {
73  sensor_msgs::CameraInfo ci;
74  ci.header = header;
75 
76  ci.height = dataHandler.getHeight();
77  ci.width = dataHandler.getWidth();
78 
79  ci.D.clear();
80  ci.D.resize(5, 0);
81  ci.D[0] = dataHandler.getCameraParameters().k1;
82  ci.D[1] = dataHandler.getCameraParameters().k2;
83  ci.D[2] = dataHandler.getCameraParameters().p1;
84  ci.D[3] = dataHandler.getCameraParameters().p2;
85  ci.D[4] = dataHandler.getCameraParameters().k3;
86 
87  for (int i = 0; i < 9; i++)
88  {
89  ci.K[i] = 0;
90  }
91  ci.K[0] = dataHandler.getCameraParameters().fx;
92  ci.K[4] = dataHandler.getCameraParameters().fy;
93  ci.K[2] = dataHandler.getCameraParameters().cx;
94  ci.K[5] = dataHandler.getCameraParameters().cy;
95  ci.K[8] = 1;
96 
97  for (int i = 0; i < 12; i++)
98  ci.P[i] = 0; // data.getCameraParameters().cam2worldMatrix[i];
99  // TODO:....
100  ci.P[0] = dataHandler.getCameraParameters().fx;
101  ci.P[5] = dataHandler.getCameraParameters().fy;
102  ci.P[10] = 1;
103  ci.P[2] = dataHandler.getCameraParameters().cx;
104  ci.P[6] = dataHandler.getCameraParameters().cy;
105 
107 }
108 
109 void publishDepth(std_msgs::Header header, VisionaryTMiniData& dataHandler)
110 {
111  std::vector<uint16_t> vec = dataHandler.getDistanceMap();
112  cv::Mat m = cv::Mat(dataHandler.getHeight(), dataHandler.getWidth(), CV_16UC1);
113  memcpy(m.data, vec.data(), vec.size() * sizeof(uint16_t));
114  sensor_msgs::ImagePtr msg =
116 
117  msg->header = header;
119 }
120 
121 void publishIntensity(std_msgs::Header header, VisionaryTMiniData& dataHandler)
122 {
123  std::vector<uint16_t> vec = dataHandler.getIntensityMap();
124  cv::Mat m = cv::Mat(dataHandler.getHeight(), dataHandler.getWidth(), CV_16UC1);
125  memcpy(m.data, vec.data(), vec.size() * sizeof(uint16_t));
126  sensor_msgs::ImagePtr msg =
128 
129  msg->header = header;
131 }
132 
133 void publishStateMap(std_msgs::Header header, VisionaryTMiniData& dataHandler)
134 {
135  std::vector<uint16_t> vec = dataHandler.getStateMap();
136  cv::Mat m = cv::Mat(dataHandler.getHeight(), dataHandler.getWidth(), CV_16UC1);
137  memcpy(m.data, vec.data(), vec.size() * sizeof(uint16_t));
138  sensor_msgs::ImagePtr msg =
140 
141  msg->header = header;
143 }
144 
145 void publishPointCloud(std_msgs::Header header, VisionaryTMiniData& dataHandler)
146 {
147  typedef sensor_msgs::PointCloud2 PointCloud;
148 
149  // Allocate new point cloud message
150  PointCloud::Ptr cloudMsg(new PointCloud);
151  cloudMsg->header = header;
152  cloudMsg->height = dataHandler.getHeight();
153  cloudMsg->width = dataHandler.getWidth();
154  cloudMsg->is_dense = false;
155  cloudMsg->is_bigendian = false;
156 
157  cloudMsg->fields.resize(5);
158  cloudMsg->fields[0].name = "x";
159  cloudMsg->fields[1].name = "y";
160  cloudMsg->fields[2].name = "z";
161  cloudMsg->fields[3].name = "intensity";
162  int offset = 0;
163  for (size_t d = 0; d < 3; ++d, offset += sizeof(float))
164  {
165  cloudMsg->fields[d].offset = offset;
166  cloudMsg->fields[d].datatype = int(sensor_msgs::PointField::FLOAT32);
167  cloudMsg->fields[d].count = 1;
168  }
169 
170  cloudMsg->fields[3].offset = offset;
171  cloudMsg->fields[3].datatype = int(sensor_msgs::PointField::UINT16);
172  cloudMsg->fields[3].count = 1;
173  offset += sizeof(uint16_t);
174 
175  cloudMsg->point_step = offset;
176  cloudMsg->row_step = cloudMsg->point_step * cloudMsg->width;
177  cloudMsg->data.resize(cloudMsg->height * cloudMsg->row_step);
178 
179  std::vector<PointXYZ> pointCloud;
180  dataHandler.generatePointCloud(pointCloud);
181  dataHandler.transformPointCloud(pointCloud);
182 
183  // simple copy to create a XYZ point cloud
184  // memcpy(&cloud_msg->data[0], &pointCloud[0], pointCloud.size()*sizeof(PointXYZ));
185 
186  std::vector<uint16_t>::const_iterator itIntens = dataHandler.getIntensityMap().begin();
187  std::vector<PointXYZ>::const_iterator itPC = pointCloud.begin();
188  size_t cloudSize = dataHandler.getHeight() * dataHandler.getWidth();
189  for (size_t index = 0; index < cloudSize; ++index, ++itIntens, ++itPC)
190  {
191  memcpy(&cloudMsg->data[index * cloudMsg->point_step + cloudMsg->fields[0].offset], &*itPC, sizeof(PointXYZ));
192  memcpy(&cloudMsg->data[index * cloudMsg->point_step + cloudMsg->fields[3].offset], &*itIntens, sizeof(uint16_t));
193  }
194  gPubPoints.publish(cloudMsg);
195 }
196 
198 {
199  bool publishedAnything = false;
200 
201  std_msgs::Header header;
202  header.stamp = ros::Time::now();
203  header.frame_id = gFrameId;
204 
206  {
207  publishedAnything = true;
208  publishCameraInfo(header, dataHandler);
209  // gPubCameraInfo_freq->tick(header.stamp);
210  }
212  {
213  publishedAnything = true;
214  publishDepth(header, dataHandler);
215  // gPubDepth_freq->tick(header.stamp);
216  }
218  {
219  publishedAnything = true;
220  publishIntensity(header, dataHandler);
221  // gPubIntensity_freq->tick(header.stamp);
222  }
224  {
225  publishedAnything = true;
226  publishStateMap(header, dataHandler);
227  // gPubStatemap_freq->tick(header.stamp);
228  }
230  {
231  publishedAnything = true;
232  publishPointCloud(header, dataHandler);
233  // gPubPoints_freq->tick(header.stamp);
234  }
235 
236  if (publishedAnything)
237  {
238  gPubCameraInfo_freq->tick(header.stamp);
239  if (gEnableDepth)
240  gPubDepth_freq->tick(header.stamp);
241  if (gEnableIntensity)
242  gPubIntensity_freq->tick(header.stamp);
243  if (gEnableStatemap)
244  gPubStatemap_freq->tick(header.stamp);
245  if (gEnablePoints)
246  gPubPoints_freq->tick(header.stamp);
247  }
248  else
249  {
250  ROS_DEBUG("Nothing published");
251  if (gControl)
252  gControl->stopAcquisition();
253  }
254 }
255 
257 {
258  gDataMtx.lock();
260  gDataMtx.unlock();
261 }
262 
263 void thr_receive_frame(std::shared_ptr<VisionaryDataStream> pDataStream,
264  std::shared_ptr<VisionaryTMiniData> pDataHandler)
265 {
266  while (gReceive)
267  {
268  if (!pDataStream->getNextFrame())
269  {
270  continue; // No valid frame received
271  }
272  if (gDataMtx.try_lock())
273  {
274  gDataHandler = pDataHandler;
275  gDataMtx.unlock();
276  boost::thread thr(&thr_publish_frame);
277  }
278  else
279  ROS_INFO("skipping frame with number %d", pDataHandler->getFrameNum());
280  }
281 }
282 
284 {
285  gNumSubs++;
286  ROS_DEBUG_STREAM("Got new subscriber, total amount of subscribers: " << gNumSubs);
287  if (gControl)
288  gControl->startAcquisition();
289 }
290 
292 {
293  gNumSubs--;
294  ROS_DEBUG_STREAM("Subscriber disconnected, total amount of subscribers: " << gNumSubs);
295 }
296 
298 {
300 }
301 
303 {
305 }
306 
308 {
310 }
311 
313 {
315 }
316 
317 int main(int argc, char** argv)
318 {
319  ros::init(argc, argv, "sick_visionary_t_mini");
320  ros::NodeHandle nh("~");
321 
322  // default parameters
323  std::string remoteDeviceIp = "192.168.1.10";
324  gFrameId = "camera";
325 
326  ros::param::get("~remote_device_ip", remoteDeviceIp);
327  ros::param::get("~frame_id", gFrameId);
328  ros::param::get("~enable_depth", gEnableDepth);
329  ros::param::get("~enable_intensity", gEnableIntensity);
330  ros::param::get("~enable_statemap", gEnableStatemap);
331  ros::param::get("~enable_points", gEnablePoints);
332 
333  std::shared_ptr<VisionaryTMiniData> pDataHandler = std::make_shared<VisionaryTMiniData>();
334  std::shared_ptr<VisionaryDataStream> pDataStream = std::make_shared<VisionaryDataStream>(pDataHandler);
335  gControl = std::make_shared<VisionaryControl>();
336 
337  ROS_INFO("Connecting to device at %s", remoteDeviceIp.c_str());
338  if (!gControl->open(VisionaryControl::ProtocolType::COLA_2, remoteDeviceIp.c_str(), 5000 /*ms*/))
339  {
340  ROS_ERROR("Connection with devices control channel failed");
341  return -1;
342  }
343  // To be sure the acquisition is currently stopped.
344  gControl->stopAcquisition();
345 
346  if (!pDataStream->open(remoteDeviceIp.c_str(), 2114u))
347  {
348  ROS_ERROR("Connection with devices data channel failed");
349  return -1;
350  }
351 
352  // TODO: add get device name and device version and print to ros info.
353  ROS_INFO("Connected with Visionary-T Mini");
354 
355  // make me public (after init.)
357  gPubCameraInfo = nh.advertise<sensor_msgs::CameraInfo>("camera_info",
358  1,
361  if (gEnableDepth)
362  gPubDepth = it.advertise("depth",
363  1,
366  if (gEnablePoints)
367  gPubPoints = nh.advertise<sensor_msgs::PointCloud2>("points",
368  2,
371  if (gEnableIntensity)
372  gPubIntensity = it.advertise("intensity",
373  1,
376  if (gEnableStatemap)
377  gPubStatemap = it.advertise("statemap",
378  1,
381 
382  gDeviceIdent = gControl->getDeviceIdent();
383 
384  // diagnostics
386  updater->setHardwareID(nh.getNamespace());
387  updater->add("driver", driver_diagnostics);
388 
389  double desiredFreq; // device max freq is 30FPS
390  ros::param::get("~desired_frequency", desiredFreq);
391  double min_freq = desiredFreq * 0.9;
392  double max_freq = desiredFreq * 1.1;
393 
394  gPubCameraInfo_freq.reset(
395  new diagnostic_updater::TopicDiagnostic("camera_info",
396  *updater,
397  diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq),
399  if (gEnableDepth)
400  gPubDepth_freq.reset(
402  *updater,
403  diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq),
405  if (gEnablePoints)
406  gPubPoints_freq.reset(
408  *updater,
409  diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq),
411  if (gEnableIntensity)
412  gPubIntensity_freq.reset(
413  new diagnostic_updater::TopicDiagnostic("intensity",
414  *updater,
415  diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq),
417  if (gEnableStatemap)
418  gPubStatemap_freq.reset(
420  *updater,
421  diagnostic_updater::FrequencyStatusParam(&min_freq, &max_freq),
423 
425 
426  // start receiver thread for camera images
427  boost::thread rec_thr(boost::bind(&thr_receive_frame, pDataStream, pDataHandler));
428 
429  // wait til end of exec.
430  ros::spin();
431 
432  gReceive = false;
433  rec_thr.join();
434 
435  gControl->stopAcquisition();
436  gControl->close();
437  pDataStream->close();
438 
439  if (gEnableDepth)
441  if (gEnablePoints)
443  if (gEnableIntensity)
445  if (gEnableStatemap)
448 
449  return 0;
450 }
gEnableIntensity
bool gEnableIntensity
Definition: visionary_t_mini.cpp:39
VisionaryControl.h
gPubStatemap
image_transport::Publisher gPubStatemap
Definition: visionary_t_mini.cpp:30
visionary::CameraParameters::fy
double fy
Definition: VisionaryData.h:27
visionary::CameraParameters::p1
double p1
Definition: VisionaryData.h:29
gPubDepth_freq
std::shared_ptr< diagnostic_updater::TopicDiagnostic > gPubDepth_freq
Definition: visionary_t_mini.cpp:34
gEnableStatemap
bool gEnableStatemap
Definition: visionary_t_mini.cpp:39
msg
msg
ros::Publisher
image_encodings.h
visionary::VisionaryTMiniData::getStateMap
const std::vector< std::uint16_t > & getStateMap() const
Definition: VisionaryTMiniData.cpp:285
image_transport::ImageTransport
visionary::VisionaryTMiniData
Definition: VisionaryTMiniData.h:17
_on_new_subscriber
void _on_new_subscriber()
Definition: visionary_t_mini.cpp:283
diagnostic_updater::TimeStampStatusParam
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
visionary::CameraParameters::cy
double cy
Definition: VisionaryData.h:27
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
visionary
Definition: MD5.cpp:44
VisionaryDataStream.h
gPubCameraInfo
ros::Publisher gPubCameraInfo
Definition: visionary_t_mini.cpp:31
ros.h
visionary::CameraParameters::fx
double fx
Camera Matrix.
Definition: VisionaryData.h:27
visionary::VisionaryData::getWidth
int getWidth() const
Definition: VisionaryData.cpp:198
publishIntensity
void publishIntensity(std_msgs::Header header, VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:121
image_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
gControl
std::shared_ptr< VisionaryControl > gControl
Definition: visionary_t_mini.cpp:26
_on_subscriber_disconnected
void _on_subscriber_disconnected()
Definition: visionary_t_mini.cpp:291
diagnostic_updater::Updater
on_new_subscriber_it
void on_new_subscriber_it(const image_transport::SingleSubscriberPublisher &)
Definition: visionary_t_mini.cpp:302
PointCloud
sensor_msgs::PointCloud2 PointCloud
visionary::CameraParameters::k3
double k3
Definition: VisionaryData.h:29
gDataMtx
boost::mutex gDataMtx
Definition: visionary_t_mini.cpp:41
on_subscriber_disconnected_it
void on_subscriber_disconnected_it(const image_transport::SingleSubscriberPublisher &)
Definition: visionary_t_mini.cpp:312
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
publisher.h
diagnostic_updater.h
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
publishCameraInfo
void publishCameraInfo(std_msgs::Header header, VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:71
visionary::PointXYZ
Definition: PointXYZ.h:10
gPubIntensity
image_transport::Publisher gPubIntensity
Definition: visionary_t_mini.cpp:30
ros::SingleSubscriberPublisher
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
gNumSubs
int gNumSubs
Definition: visionary_t_mini.cpp:44
publish_frame
void publish_frame(VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:197
publishDepth
void publishDepth(std_msgs::Header header, VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:109
ros::Publisher::shutdown
void shutdown()
updater
std::shared_ptr< diagnostic_updater::Updater > updater
Definition: visionary_t_mini.cpp:33
visionary::VisionaryData::getCameraParameters
const CameraParameters & getCameraParameters() const
Definition: VisionaryData.cpp:235
ROS_DEBUG
#define ROS_DEBUG(...)
thr_receive_frame
void thr_receive_frame(std::shared_ptr< VisionaryDataStream > pDataStream, std::shared_ptr< VisionaryTMiniData > pDataHandler)
Definition: visionary_t_mini.cpp:263
gPubIntensity_freq
std::shared_ptr< diagnostic_updater::TopicDiagnostic > gPubIntensity_freq
Definition: visionary_t_mini.cpp:34
visionary::VisionaryTMiniData::getDistanceMap
const std::vector< std::uint16_t > & getDistanceMap() const
Definition: VisionaryTMiniData.cpp:275
driver_diagnostics
void driver_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: visionary_t_mini.cpp:51
image_transport::Publisher::shutdown
void shutdown()
visionary::VisionaryTMiniData::getIntensityMap
const std::vector< std::uint16_t > & getIntensityMap() const
Definition: VisionaryTMiniData.cpp:280
d
d
ros::TimerEvent
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
visionary::CameraParameters::cx
double cx
Definition: VisionaryData.h:27
gPubDepth
image_transport::Publisher gPubDepth
Definition: visionary_t_mini.cpp:30
on_subscriber_disconnected_ros
void on_subscriber_disconnected_ros(const ros::SingleSubscriberPublisher &)
Definition: visionary_t_mini.cpp:307
image_transport::SingleSubscriberPublisher
image_transport.h
gPubCameraInfo_freq
std::shared_ptr< diagnostic_updater::TopicDiagnostic > gPubCameraInfo_freq
Definition: visionary_t_mini.cpp:35
diagnostic_updater::TopicDiagnostic
gDataHandler
std::shared_ptr< VisionaryTMiniData > gDataHandler
Definition: visionary_t_mini.cpp:28
boost::iterators::i
D const & i
Definition: iterator_facade.hpp:956
visionary::CameraParameters::k2
double k2
Definition: VisionaryData.h:29
diag_timer_cb
void diag_timer_cb(const ros::TimerEvent &)
Definition: visionary_t_mini.cpp:46
publishPointCloud
void publishPointCloud(std_msgs::Header header, VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:145
visionary::VisionaryData::transformPointCloud
void transformPointCloud(std::vector< PointXYZ > &pointCloud) const
Definition: VisionaryData.cpp:171
VisionaryTMiniData.h
gEnablePoints
bool gEnablePoints
Definition: visionary_t_mini.cpp:39
gPubStatemap_freq
std::shared_ptr< diagnostic_updater::TopicDiagnostic > gPubStatemap_freq
Definition: visionary_t_mini.cpp:34
image_transport::Publisher
cv_bridge.h
gPubPoints
ros::Publisher gPubPoints
Definition: visionary_t_mini.cpp:31
ROS_ERROR
#define ROS_ERROR(...)
visionary::VisionaryTMiniData::generatePointCloud
void generatePointCloud(std::vector< PointXYZ > &pointCloud) override
Definition: VisionaryTMiniData.cpp:270
cv_bridge::CvImage
visionary::VisionaryData::getHeight
int getHeight() const
Definition: VisionaryData.cpp:193
diagnostic_updater::DiagnosticStatusWrapper
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
gEnableDepth
bool gEnableDepth
Definition: visionary_t_mini.cpp:39
visionary::CameraParameters::p2
double p2
Definition: VisionaryData.h:29
ros::spin
ROSCPP_DECL void spin()
publishStateMap
void publishStateMap(std_msgs::Header header, VisionaryTMiniData &dataHandler)
Definition: visionary_t_mini.cpp:133
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
gPubPoints_freq
std::shared_ptr< diagnostic_updater::TopicDiagnostic > gPubPoints_freq
Definition: visionary_t_mini.cpp:35
header
const std::string header
gFrameId
std::string gFrameId
Definition: visionary_t_mini.cpp:37
ROS_INFO
#define ROS_INFO(...)
gDeviceIdent
std::string gDeviceIdent
Definition: visionary_t_mini.cpp:38
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
main
int main(int argc, char **argv)
Definition: visionary_t_mini.cpp:317
ros::Duration
ros::Timer
gReceive
bool gReceive
Definition: visionary_t_mini.cpp:42
visionary::CameraParameters::k1
double k1
Camera Distortion Parameters.
Definition: VisionaryData.h:29
ros::NodeHandle
on_new_subscriber_ros
void on_new_subscriber_ros(const ros::SingleSubscriberPublisher &)
Definition: visionary_t_mini.cpp:297
thr_publish_frame
void thr_publish_frame()
Definition: visionary_t_mini.cpp:256
ros::Time::now
static Time now()
diagnostic_updater::FrequencyStatusParam


sick_visionary_ros
Author(s): SICK AG TechSupport 3D Snapshot
autogenerated on Thu Feb 8 2024 03:56:19