15 #ifndef __NERIAN_STEREO_NODE_H__ 16 #define __NERIAN_STEREO_NODE_H__ 20 #include <boost/smart_ptr.hpp> 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> 29 #include <sensor_msgs/PointCloud2.h> 30 #include <sensor_msgs/Image.h> 31 #include <dynamic_reconfigure/server.h> 35 #include <geometry_msgs/TransformStamped.h> 38 #include <opencv2/opencv.hpp> 40 #include <colorcoder.h> 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> 89 void initDynamicReconfigure();
94 void initDataChannelService();
99 void prepareAsyncTransfer();
104 void processOneImageSet();
109 void processDataChannels();
114 void publishTransform();
138 boost::scoped_ptr<dynamic_reconfigure::Server<nerian_stereo::NerianStereoConfig>>
dynReconfServer;
176 int lastLogFrames = 0;
186 void loadCameraCalibration();
192 void publishImageMsg(
const ImageSet& imageSet,
int imageIndex,
ros::Time stamp,
bool allowColorCode,
199 void qMatrixToRosCoords(
const float* src,
float* dst);
205 void publishPointCloudMsg(ImageSet& imageSet,
ros::Time stamp);
210 template <Po
intCloudColorMode colorMode>
void copyPointCloudIntensity(ImageSet& imageSet);
216 template <
int coord>
void copyPointCloudClamped(
float* src,
float* dst,
int size);
222 void initPointCloud();
227 void publishCameraInfo(
ros::Time stamp,
const ImageSet& imageSet);
232 template<
class T>
void readCalibrationArray(
const char* key, T& dest);
237 void dynamicReconfigureCallback(nerian_stereo::NerianStereoConfig &config, uint32_t level);
242 void updateParameterServerFromDevice(param::ParameterSet& cfg);
247 void updateDynamicReconfigureFromDevice(param::ParameterSet& cfg);
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);
std::string internalFrame
sensor_msgs::PointCloud2Ptr pointCloudMsg
boost::scoped_ptr< dynamic_reconfigure::Server< nerian_stereo::NerianStereoConfig > > dynReconfServer
boost::scoped_ptr< ColorCoder > colCoder
boost::scoped_ptr< DataChannelService > dataChannelService
nerian_stereo::StereoCameraInfoPtr camInfoMsg
bool initialConfigReceived
void init(const M_string &remappings)
boost::scoped_ptr< ros::Publisher > rightImagePublisher
cv::FileStorage calibStorage
geometry_msgs::TransformStamped currentTransform
cv::Mat_< cv::Vec3b > colDispMap
PointCloudColorMode pointCloudColorMode
boost::scoped_ptr< ros::Publisher > thirdImagePublisher
boost::scoped_ptr< Reconstruct3D > recon3d
ros::Time lastCamInfoPublish
boost::scoped_ptr< ros::Publisher > cloudPublisher
boost::scoped_ptr< ros::Publisher > disparityPublisher
boost::scoped_ptr< tf2_ros::TransformBroadcaster > transformBroadcaster
A driver node that receives data from Nerian stereo devices and forwards it to ROS.
boost::scoped_ptr< ros::Publisher > leftImagePublisher
boost::scoped_ptr< DeviceParameters > deviceParameters
std::string colorCodeDispMap
boost::scoped_ptr< ros::Publisher > cameraInfoPublisher
nerian_stereo::NerianStereoConfig lastKnownConfig
boost::scoped_ptr< AsyncTransfer > asyncTransfer