nerian_stereo_node_base.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Copyright (c) 2022 Nerian Vision GmbH
3  *
4  * Permission is hereby granted, free of charge, to any person obtaining a copy
5  * of this software and associated documentation files (the "Software"), to deal
6  * in the Software without restriction, including without limitation the rights
7  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8  * copies of the Software, and to permit persons to whom the Software is
9  * furnished to do so, subject to the following conditions:
10  *
11  * The above copyright notice and this permission notice shall be included in
12  * all copies or substantial portions of the Software.
13  *******************************************************************************/
14 
15 #ifndef __NERIAN_STEREO_NODE_H__
16 #define __NERIAN_STEREO_NODE_H__
17 
18 #include <iostream>
19 #include <iomanip>
20 #include <boost/smart_ptr.hpp>
21 
22 #include <visiontransfer/asynctransfer.h>
23 #include <visiontransfer/reconstruct3d.h>
24 #include <visiontransfer/deviceparameters.h>
25 #include <visiontransfer/exceptions.h>
26 #include <visiontransfer/datachannelservice.h>
27 
28 #include <ros/ros.h>
29 #include <sensor_msgs/PointCloud2.h>
30 #include <sensor_msgs/Image.h>
31 #include <dynamic_reconfigure/server.h>
35 #include <geometry_msgs/TransformStamped.h>
36 
37 #include <cv_bridge/cv_bridge.h>
38 #include <opencv2/opencv.hpp>
39 
40 #include <colorcoder.h>
41 
42 #include <nerian_stereo/NerianStereoConfig.h>
43 #include <nerian_stereo/StereoCameraInfo.h>
44 #include <visiontransfer/deviceparameters.h>
45 #include <visiontransfer/parameterset.h>
46 #include <visiontransfer/exceptions.h>
47 
48 using namespace std;
49 using namespace visiontransfer;
50 
71 namespace nerian_stereo {
72 
74 public:
75  StereoNodeBase(): initialConfigReceived(false), frameNum(0) {
76  }
77 
79  }
80 
84  void init();
85 
86  /*
87  * \brief Initialize and publish configuration with a dynamic_reconfigure server
88  */
89  void initDynamicReconfigure();
90 
91  /*
92  * \brief Initialize the data channel service (for receiving e.g. internal IMU data)
93  */
94  void initDataChannelService();
95 
99  void prepareAsyncTransfer();
100 
101  /*
102  * \brief Collect and process a single image set (or return after timeout if none are available)
103  */
104  void processOneImageSet();
105 
106  /*
107  * \brief Queries the the supplemental data channels (IMU ...) for new data and updates ROS accordingly
108  */
109  void processDataChannels();
110 
111  /*
112  * \brief Publishes an update for the ROS transform
113  */
114  void publishTransform();
115 
116 private:
121  NONE
122  };
123 
124  virtual ros::NodeHandle& getNH() = 0;
125  virtual ros::NodeHandle& getPrivateNH() = 0;
126 
127  //
128  boost::scoped_ptr<ros::Publisher> cloudPublisher;
129  boost::scoped_ptr<ros::Publisher> disparityPublisher;
130  boost::scoped_ptr<ros::Publisher> leftImagePublisher;
131  boost::scoped_ptr<ros::Publisher> rightImagePublisher;
132  boost::scoped_ptr<ros::Publisher> thirdImagePublisher;
133  boost::scoped_ptr<ros::Publisher> cameraInfoPublisher;
134 
135  boost::scoped_ptr<tf2_ros::TransformBroadcaster> transformBroadcaster;
136 
137  // ROS dynamic_reconfigure
138  boost::scoped_ptr<dynamic_reconfigure::Server<nerian_stereo::NerianStereoConfig>> dynReconfServer;
139  nerian_stereo::NerianStereoConfig lastKnownConfig;
141 
142  // Connection to parameter server on device
143  boost::scoped_ptr<DeviceParameters> deviceParameters;
144 
145  // Parameters
146  bool useTcp;
147  std::string colorCodeDispMap;
151  std::string remotePort;
152  std::string frame; // outer frame (e.g. world)
153  std::string internalFrame; // our private frame / Transform we publish
154  std::string remoteHost;
155  std::string calibFile;
156  double execDelay;
157  double maxDepth;
160 
161  // Other members
162  int frameNum;
163  boost::scoped_ptr<Reconstruct3D> recon3d;
164  boost::scoped_ptr<ColorCoder> colCoder;
165  cv::Mat_<cv::Vec3b> colDispMap;
166  sensor_msgs::PointCloud2Ptr pointCloudMsg;
167  cv::FileStorage calibStorage;
168  nerian_stereo::StereoCameraInfoPtr camInfoMsg;
170 
171  // Active channels in the previous ImageSet
172  bool hadLeft, hadRight, hadColor, hadDisparity;
173 
174  boost::scoped_ptr<AsyncTransfer> asyncTransfer;
176  int lastLogFrames = 0;
177 
178  // DataChannelService connection, to obtain IMU data
179  boost::scoped_ptr<DataChannelService> dataChannelService;
180  // Our transform, updated with polled IMU data (if available)
181  geometry_msgs::TransformStamped currentTransform;
182 
186  void loadCameraCalibration();
187 
192  void publishImageMsg(const ImageSet& imageSet, int imageIndex, ros::Time stamp, bool allowColorCode,
193  ros::Publisher* publisher);
194 
199  void qMatrixToRosCoords(const float* src, float* dst);
200 
205  void publishPointCloudMsg(ImageSet& imageSet, ros::Time stamp);
206 
210  template <PointCloudColorMode colorMode> void copyPointCloudIntensity(ImageSet& imageSet);
211 
216  template <int coord> void copyPointCloudClamped(float* src, float* dst, int size);
217 
222  void initPointCloud();
223 
227  void publishCameraInfo(ros::Time stamp, const ImageSet& imageSet);
228 
232  template<class T> void readCalibrationArray(const char* key, T& dest);
233 
234  /*
235  * \brief Callback that receives an updated configuration from ROS; internally uses autogen_dynamicReconfigureCallback
236  */
237  void dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level);
238 
239  /*
240  * \brief Forward parameters from the device as initial values to the ROS parameter server; internally uses autogen_updateParameterServerFromDevice
241  */
242  void updateParameterServerFromDevice(param::ParameterSet& cfg);
243 
244  /*
245  * \brief Uses parameters from the device as a run-time override for limits and defaults in the dynamic_reconfigure node; internally uses autogen_updateDynamicReconfigureFromDevice
246  */
247  void updateDynamicReconfigureFromDevice(param::ParameterSet& cfg);
248 
249 
250  // The following three implementations are autogenerated by generate_nerian_config_cpp.py
251  // by parsing cfg/NerianStereo.cfg (which is also used by dynamic_reconfigure)
255  void autogen_dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level);
259  void autogen_updateParameterServerFromDevice(param::ParameterSet& cfg);
263  void autogen_updateDynamicReconfigureFromDevice(param::ParameterSet& cfg);
264 
265 };
266 
267 } // namespace
268 
269 #endif
270 
nerian_stereo::StereoNodeBase::rosCoordinateSystem
bool rosCoordinateSystem
Definition: nerian_stereo_node_base.h:149
nerian_stereo::StereoNodeBase::lastKnownConfig
nerian_stereo::NerianStereoConfig lastKnownConfig
Definition: nerian_stereo_node_base.h:139
nerian_stereo::StereoNodeBase::rightImagePublisher
boost::scoped_ptr< ros::Publisher > rightImagePublisher
Definition: nerian_stereo_node_base.h:131
nerian_stereo::StereoNodeBase::maxDepth
double maxDepth
Definition: nerian_stereo_node_base.h:157
nerian_stereo::StereoNodeBase::cameraInfoPublisher
boost::scoped_ptr< ros::Publisher > cameraInfoPublisher
Definition: nerian_stereo_node_base.h:133
nerian_stereo::StereoNodeBase::currentTransform
geometry_msgs::TransformStamped currentTransform
Definition: nerian_stereo_node_base.h:181
ros::Publisher
nerian_stereo::StereoNodeBase::initialConfigReceived
bool initialConfigReceived
Definition: nerian_stereo_node_base.h:140
nerian_stereo::StereoNodeBase::camInfoMsg
nerian_stereo::StereoCameraInfoPtr camInfoMsg
Definition: nerian_stereo_node_base.h:168
nerian_stereo::StereoNodeBase::remotePort
std::string remotePort
Definition: nerian_stereo_node_base.h:151
nerian_stereo::StereoNodeBase::transformBroadcaster
boost::scoped_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
Definition: nerian_stereo_node_base.h:135
ros.h
nerian_stereo::StereoNodeBase::colDispMap
cv::Mat_< cv::Vec3b > colDispMap
Definition: nerian_stereo_node_base.h:165
nerian_stereo::StereoNodeBase::rosTimestamps
bool rosTimestamps
Definition: nerian_stereo_node_base.h:150
nerian_stereo::StereoNodeBase::execDelay
double execDelay
Definition: nerian_stereo_node_base.h:156
nerian_stereo::StereoNodeBase::pointCloudMsg
sensor_msgs::PointCloud2Ptr pointCloudMsg
Definition: nerian_stereo_node_base.h:166
nerian_stereo::StereoNodeBase::internalFrame
std::string internalFrame
Definition: nerian_stereo_node_base.h:153
transform_broadcaster.h
nerian_stereo::StereoNodeBase::hadRight
bool hadRight
Definition: nerian_stereo_node_base.h:172
nerian_stereo::StereoNodeBase::calibStorage
cv::FileStorage calibStorage
Definition: nerian_stereo_node_base.h:167
nerian_stereo::StereoNodeBase::disparityPublisher
boost::scoped_ptr< ros::Publisher > disparityPublisher
Definition: nerian_stereo_node_base.h:129
nerian_stereo::StereoNodeBase::RGB_COMBINED
@ RGB_COMBINED
Definition: nerian_stereo_node_base.h:119
nerian_stereo::StereoNodeBase::INTENSITY
@ INTENSITY
Definition: nerian_stereo_node_base.h:120
Quaternion.h
nerian_stereo::StereoNodeBase::pointCloudColorMode
PointCloudColorMode pointCloudColorMode
Definition: nerian_stereo_node_base.h:159
nerian_stereo::StereoNodeBase
Definition: nerian_stereo_node_base.h:73
nerian_stereo::StereoNodeBase::thirdImagePublisher
boost::scoped_ptr< ros::Publisher > thirdImagePublisher
Definition: nerian_stereo_node_base.h:132
nerian_stereo::StereoNodeBase::frameNum
int frameNum
Definition: nerian_stereo_node_base.h:162
nerian_stereo::StereoNodeBase::leftImagePublisher
boost::scoped_ptr< ros::Publisher > leftImagePublisher
Definition: nerian_stereo_node_base.h:130
nerian_stereo::StereoNodeBase::colorCodeDispMap
std::string colorCodeDispMap
Definition: nerian_stereo_node_base.h:147
nerian_stereo::StereoNodeBase::calibFile
std::string calibFile
Definition: nerian_stereo_node_base.h:155
nerian_stereo::StereoNodeBase::remoteHost
std::string remoteHost
Definition: nerian_stereo_node_base.h:154
nerian_stereo::StereoNodeBase::lastCamInfoPublish
ros::Time lastCamInfoPublish
Definition: nerian_stereo_node_base.h:169
nerian_stereo::StereoNodeBase::~StereoNodeBase
~StereoNodeBase()
Definition: nerian_stereo_node_base.h:78
nerian_stereo::StereoNodeBase::colorCodeLegend
bool colorCodeLegend
Definition: nerian_stereo_node_base.h:148
nerian_stereo::StereoNodeBase::StereoNodeBase
StereoNodeBase()
Definition: nerian_stereo_node_base.h:75
ros::Time
nerian_stereo::StereoNodeBase::colCoder
boost::scoped_ptr< ColorCoder > colCoder
Definition: nerian_stereo_node_base.h:164
nerian_stereo::StereoNodeBase::useQFromCalibFile
bool useQFromCalibFile
Definition: nerian_stereo_node_base.h:158
std
cv_bridge.h
nerian_stereo::StereoNodeBase::frame
std::string frame
Definition: nerian_stereo_node_base.h:152
nerian_stereo::StereoNodeBase::deviceParameters
boost::scoped_ptr< DeviceParameters > deviceParameters
Definition: nerian_stereo_node_base.h:143
init
void init(const M_string &remappings)
nerian_stereo::StereoNodeBase::PointCloudColorMode
PointCloudColorMode
Definition: nerian_stereo_node_base.h:117
nerian_stereo::StereoNodeBase::cloudPublisher
boost::scoped_ptr< ros::Publisher > cloudPublisher
Definition: nerian_stereo_node_base.h:128
nerian_stereo::StereoNodeBase::RGB_SEPARATE
@ RGB_SEPARATE
Definition: nerian_stereo_node_base.h:118
nerian_stereo
A driver node that receives data from Nerian stereo devices and forwards it to ROS.
Definition: nerian_stereo_node.cpp:17
nerian_stereo::StereoNodeBase::recon3d
boost::scoped_ptr< Reconstruct3D > recon3d
Definition: nerian_stereo_node_base.h:163
nerian_stereo::StereoNodeBase::lastLogTime
ros::Time lastLogTime
Definition: nerian_stereo_node_base.h:175
Matrix3x3.h
nerian_stereo::StereoNodeBase::useTcp
bool useTcp
Definition: nerian_stereo_node_base.h:146
nerian_stereo::StereoNodeBase::dynReconfServer
boost::scoped_ptr< dynamic_reconfigure::Server< nerian_stereo::NerianStereoConfig > > dynReconfServer
Definition: nerian_stereo_node_base.h:138
nerian_stereo::StereoNodeBase::dataChannelService
boost::scoped_ptr< DataChannelService > dataChannelService
Definition: nerian_stereo_node_base.h:179
ros::NodeHandle
nerian_stereo::StereoNodeBase::asyncTransfer
boost::scoped_ptr< AsyncTransfer > asyncTransfer
Definition: nerian_stereo_node_base.h:174


nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Wed Jan 24 2024 04:06:47