Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
nerian_stereo::StereoNodeBase Class Referenceabstract

#include <nerian_stereo_node_base.h>

Inheritance diagram for nerian_stereo::StereoNodeBase:
Inheritance graph
[legend]

Public Member Functions

void init ()
 Performs general initializations. More...
 
void initDataChannelService ()
 
void initDynamicReconfigure ()
 
void prepareAsyncTransfer ()
 Connects to the image service to request the stream of image sets. More...
 
void processDataChannels ()
 
void processOneImageSet ()
 
void publishTransform ()
 
 StereoNodeBase ()
 
 ~StereoNodeBase ()
 

Private Types

enum  PointCloudColorMode { RGB_SEPARATE, RGB_COMBINED, INTENSITY, NONE }
 

Private Member Functions

void autogen_dynamicReconfigureCallback (nerian_stereo::NerianStereoConfig &config, uint32_t level)
 Auto-generated code to check for parameter changes and forward them to the device. More...
 
void autogen_updateDynamicReconfigureFromDevice (std::map< std::string, ParameterInfo > &cfg)
 Auto-generated code to override the dynamic_reconfigure limits and defaults for all parameters. More...
 
void autogen_updateParameterServerFromDevice (std::map< std::string, ParameterInfo > &cfg)
 Auto-generated code to set initial parameters according to those obtained from the device. More...
 
template<int coord>
void copyPointCloudClamped (float *src, float *dst, int size)
 Copies all points in a point cloud that have a depth smaller than maxDepth. Other points are set to NaN. More...
 
template<PointCloudColorMode colorMode>
void copyPointCloudIntensity (ImageSet &imageSet)
 Copies the intensity or RGB data to the point cloud. More...
 
void dynamicReconfigureCallback (nerian_stereo::NerianStereoConfig &config, uint32_t level)
 
virtual ros::NodeHandlegetNH ()=0
 
virtual ros::NodeHandlegetPrivateNH ()=0
 
void initPointCloud ()
 Performs all neccessary initializations for point cloud+ publishing. More...
 
void loadCameraCalibration ()
 Loads a camera calibration file if configured. More...
 
void publishCameraInfo (ros::Time stamp, const ImageSet &imageSet)
 Publishes the camera info once per second. More...
 
void publishImageMsg (const ImageSet &imageSet, int imageIndex, ros::Time stamp, bool allowColorCode, ros::Publisher *publisher)
 Publishes the disparity map as 16-bit grayscale image or color coded RGB image. More...
 
void publishPointCloudMsg (ImageSet &imageSet, ros::Time stamp)
 Reconstructs the 3D locations form the disparity map and publishes them as point cloud. More...
 
void qMatrixToRosCoords (const float *src, float *dst)
 Transform Q matrix to match the ROS coordinate system: Swap y/z axis, then swap x/y axis, then invert y and z axis. More...
 
template<class T >
void readCalibrationArray (const char *key, T &dest)
 Reads a vector from the calibration file to a boost:array. More...
 
void updateDynamicReconfigureFromDevice (std::map< std::string, ParameterInfo > &cfg)
 
void updateParameterServerFromDevice (std::map< std::string, ParameterInfo > &cfg)
 

Private Attributes

boost::scoped_ptr< AsyncTransfer > asyncTransfer
 
std::string calibFile
 
cv::FileStorage calibStorage
 
boost::scoped_ptr< ros::PublishercameraInfoPublisher
 
nerian_stereo::StereoCameraInfoPtr camInfoMsg
 
boost::scoped_ptr< ros::PublishercloudPublisher
 
boost::scoped_ptr< ColorCoder > colCoder
 
cv::Mat_< cv::Vec3b > colDispMap
 
std::string colorCodeDispMap
 
bool colorCodeLegend
 
geometry_msgs::TransformStamped currentTransform
 
boost::scoped_ptr< DataChannelService > dataChannelService
 
boost::scoped_ptr< DeviceParameters > deviceParameters
 
boost::scoped_ptr< ros::PublisherdisparityPublisher
 
boost::scoped_ptr< dynamic_reconfigure::Server< nerian_stereo::NerianStereoConfig > > dynReconfServer
 
double execDelay
 
std::string frame
 
int frameNum
 
bool initialConfigReceived
 
std::string internalFrame
 
ros::Time lastCamInfoPublish
 
nerian_stereo::NerianStereoConfig lastKnownConfig
 
int lastLogFrames = 0
 
ros::Time lastLogTime
 
boost::scoped_ptr< ros::PublisherleftImagePublisher
 
double maxDepth
 
PointCloudColorMode pointCloudColorMode
 
sensor_msgs::PointCloud2Ptr pointCloudMsg
 
boost::scoped_ptr< Reconstruct3D > recon3d
 
std::string remoteHost
 
std::string remotePort
 
boost::scoped_ptr< ros::PublisherrightImagePublisher
 
bool rosCoordinateSystem
 
bool rosTimestamps
 
boost::scoped_ptr< tf2_ros::TransformBroadcastertransformBroadcaster
 
bool useQFromCalibFile
 
bool useTcp
 

Detailed Description

Definition at line 72 of file nerian_stereo_node_base.h.

Member Enumeration Documentation

Enumerator
RGB_SEPARATE 
RGB_COMBINED 
INTENSITY 
NONE 

Definition at line 116 of file nerian_stereo_node_base.h.

Constructor & Destructor Documentation

nerian_stereo::StereoNodeBase::StereoNodeBase ( )
inline

Definition at line 74 of file nerian_stereo_node_base.h.

nerian_stereo::StereoNodeBase::~StereoNodeBase ( )
inline

Definition at line 77 of file nerian_stereo_node_base.h.

Member Function Documentation

void nerian_stereo::StereoNodeBase::autogen_dynamicReconfigureCallback ( nerian_stereo::NerianStereoConfig &  config,
uint32_t  level 
)
private

Auto-generated code to check for parameter changes and forward them to the device.

void nerian_stereo::StereoNodeBase::autogen_updateDynamicReconfigureFromDevice ( std::map< std::string, ParameterInfo > &  cfg)
private

Auto-generated code to override the dynamic_reconfigure limits and defaults for all parameters.

void nerian_stereo::StereoNodeBase::autogen_updateParameterServerFromDevice ( std::map< std::string, ParameterInfo > &  cfg)
private

Auto-generated code to set initial parameters according to those obtained from the device.

template<int coord>
void nerian_stereo::StereoNodeBase::copyPointCloudClamped ( float *  src,
float *  dst,
int  size 
)
private

Copies all points in a point cloud that have a depth smaller than maxDepth. Other points are set to NaN.

Definition at line 520 of file nerian_stereo_node_base.cpp.

template<StereoNodeBase::PointCloudColorMode colorMode>
void nerian_stereo::StereoNodeBase::copyPointCloudIntensity ( ImageSet &  imageSet)
private

Copies the intensity or RGB data to the point cloud.

Definition at line 431 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::dynamicReconfigureCallback ( nerian_stereo::NerianStereoConfig &  config,
uint32_t  level 
)
private

Definition at line 19 of file nerian_stereo_node_base.cpp.

virtual ros::NodeHandle& nerian_stereo::StereoNodeBase::getNH ( )
privatepure virtual
virtual ros::NodeHandle& nerian_stereo::StereoNodeBase::getPrivateNH ( )
privatepure virtual
void nerian_stereo::StereoNodeBase::init ( )

Performs general initializations.

Definition at line 76 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::initDataChannelService ( )

Definition at line 178 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::initDynamicReconfigure ( )

Definition at line 44 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::initPointCloud ( )
private

Performs all neccessary initializations for point cloud+ publishing.

Definition at line 536 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::loadCameraCalibration ( )
private

Loads a camera calibration file if configured.

Definition at line 241 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::prepareAsyncTransfer ( )

Connects to the image service to request the stream of image sets.

Definition at line 182 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::processDataChannels ( )

Definition at line 690 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::processOneImageSet ( )

Definition at line 188 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::publishCameraInfo ( ros::Time  stamp,
const ImageSet &  imageSet 
)
private

Publishes the camera info once per second.

Definition at line 606 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::publishImageMsg ( const ImageSet &  imageSet,
int  imageIndex,
ros::Time  stamp,
bool  allowColorCode,
ros::Publisher publisher 
)
private

Publishes the disparity map as 16-bit grayscale image or color coded RGB image.

Definition at line 260 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::publishPointCloudMsg ( ImageSet &  imageSet,
ros::Time  stamp 
)
private

Reconstructs the 3D locations form the disparity map and publishes them as point cloud.

Definition at line 348 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::publishTransform ( )

Definition at line 740 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::qMatrixToRosCoords ( const float *  src,
float *  dst 
)
private

Transform Q matrix to match the ROS coordinate system: Swap y/z axis, then swap x/y axis, then invert y and z axis.

Definition at line 334 of file nerian_stereo_node_base.cpp.

template<class T >
void nerian_stereo::StereoNodeBase::readCalibrationArray ( const char *  key,
T &  dest 
)
private

Reads a vector from the calibration file to a boost:array.

Definition at line 679 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::updateDynamicReconfigureFromDevice ( std::map< std::string, ParameterInfo > &  cfg)
private

Definition at line 38 of file nerian_stereo_node_base.cpp.

void nerian_stereo::StereoNodeBase::updateParameterServerFromDevice ( std::map< std::string, ParameterInfo > &  cfg)
private

Definition at line 31 of file nerian_stereo_node_base.cpp.

Member Data Documentation

boost::scoped_ptr<AsyncTransfer> nerian_stereo::StereoNodeBase::asyncTransfer
private

Definition at line 169 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::calibFile
private

Definition at line 153 of file nerian_stereo_node_base.h.

cv::FileStorage nerian_stereo::StereoNodeBase::calibStorage
private

Definition at line 165 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ros::Publisher> nerian_stereo::StereoNodeBase::cameraInfoPublisher
private

Definition at line 131 of file nerian_stereo_node_base.h.

nerian_stereo::StereoCameraInfoPtr nerian_stereo::StereoNodeBase::camInfoMsg
private

Definition at line 166 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ros::Publisher> nerian_stereo::StereoNodeBase::cloudPublisher
private

Definition at line 127 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ColorCoder> nerian_stereo::StereoNodeBase::colCoder
private

Definition at line 162 of file nerian_stereo_node_base.h.

cv::Mat_<cv::Vec3b> nerian_stereo::StereoNodeBase::colDispMap
private

Definition at line 163 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::colorCodeDispMap
private

Definition at line 145 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::colorCodeLegend
private

Definition at line 146 of file nerian_stereo_node_base.h.

geometry_msgs::TransformStamped nerian_stereo::StereoNodeBase::currentTransform
private

Definition at line 176 of file nerian_stereo_node_base.h.

boost::scoped_ptr<DataChannelService> nerian_stereo::StereoNodeBase::dataChannelService
private

Definition at line 174 of file nerian_stereo_node_base.h.

boost::scoped_ptr<DeviceParameters> nerian_stereo::StereoNodeBase::deviceParameters
private

Definition at line 141 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ros::Publisher> nerian_stereo::StereoNodeBase::disparityPublisher
private

Definition at line 128 of file nerian_stereo_node_base.h.

boost::scoped_ptr<dynamic_reconfigure::Server<nerian_stereo::NerianStereoConfig> > nerian_stereo::StereoNodeBase::dynReconfServer
private

Definition at line 136 of file nerian_stereo_node_base.h.

double nerian_stereo::StereoNodeBase::execDelay
private

Definition at line 154 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::frame
private

Definition at line 150 of file nerian_stereo_node_base.h.

int nerian_stereo::StereoNodeBase::frameNum
private

Definition at line 160 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::initialConfigReceived
private

Definition at line 138 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::internalFrame
private

Definition at line 151 of file nerian_stereo_node_base.h.

ros::Time nerian_stereo::StereoNodeBase::lastCamInfoPublish
private

Definition at line 167 of file nerian_stereo_node_base.h.

nerian_stereo::NerianStereoConfig nerian_stereo::StereoNodeBase::lastKnownConfig
private

Definition at line 137 of file nerian_stereo_node_base.h.

int nerian_stereo::StereoNodeBase::lastLogFrames = 0
private

Definition at line 171 of file nerian_stereo_node_base.h.

ros::Time nerian_stereo::StereoNodeBase::lastLogTime
private

Definition at line 170 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ros::Publisher> nerian_stereo::StereoNodeBase::leftImagePublisher
private

Definition at line 129 of file nerian_stereo_node_base.h.

double nerian_stereo::StereoNodeBase::maxDepth
private

Definition at line 155 of file nerian_stereo_node_base.h.

PointCloudColorMode nerian_stereo::StereoNodeBase::pointCloudColorMode
private

Definition at line 157 of file nerian_stereo_node_base.h.

sensor_msgs::PointCloud2Ptr nerian_stereo::StereoNodeBase::pointCloudMsg
private

Definition at line 164 of file nerian_stereo_node_base.h.

boost::scoped_ptr<Reconstruct3D> nerian_stereo::StereoNodeBase::recon3d
private

Definition at line 161 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::remoteHost
private

Definition at line 152 of file nerian_stereo_node_base.h.

std::string nerian_stereo::StereoNodeBase::remotePort
private

Definition at line 149 of file nerian_stereo_node_base.h.

boost::scoped_ptr<ros::Publisher> nerian_stereo::StereoNodeBase::rightImagePublisher
private

Definition at line 130 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::rosCoordinateSystem
private

Definition at line 147 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::rosTimestamps
private

Definition at line 148 of file nerian_stereo_node_base.h.

boost::scoped_ptr<tf2_ros::TransformBroadcaster> nerian_stereo::StereoNodeBase::transformBroadcaster
private

Definition at line 133 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::useQFromCalibFile
private

Definition at line 156 of file nerian_stereo_node_base.h.

bool nerian_stereo::StereoNodeBase::useTcp
private

Definition at line 144 of file nerian_stereo_node_base.h.


The documentation for this class was generated from the following files:


nerian_stereo
Author(s): Nerian Vision Technologies
autogenerated on Fri Apr 16 2021 02:11:19