#include <nerian_stereo_node_base.h>
Public Member Functions | |
void | init () |
Performs general initializations. More... | |
void | initDynamicReconfigure () |
void | prepareAsyncTransfer () |
Connects to the image service to request the stream of image pairs. More... | |
void | processOneImagePair () |
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 (ImagePair &imagePair) |
Copies the intensity or RGB data to the point cloud. More... | |
void | dynamicReconfigureCallback (nerian_stereo::NerianStereoConfig &config, uint32_t level) |
virtual ros::NodeHandle & | getNH ()=0 |
virtual ros::NodeHandle & | getPrivateNH ()=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 ImagePair &imagePair) |
Publishes the camera info once per second. More... | |
void | publishImageMsg (const ImagePair &imagePair, 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 (ImagePair &imagePair, 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::Publisher > | cameraInfoPublisher |
nerian_stereo::StereoCameraInfoPtr | camInfoMsg |
boost::scoped_ptr< ros::Publisher > | cloudPublisher |
boost::scoped_ptr< ColorCoder > | colCoder |
cv::Mat_< cv::Vec3b > | colDispMap |
std::string | colorCodeDispMap |
bool | colorCodeLegend |
boost::scoped_ptr< ros::Publisher > | disparityPublisher |
boost::scoped_ptr< dynamic_reconfigure::Server< nerian_stereo::NerianStereoConfig > > | dynReconfServer |
double | execDelay |
std::string | frame |
int | frameNum |
bool | initialConfigReceived |
ros::Time | lastCamInfoPublish |
nerian_stereo::NerianStereoConfig | lastKnownConfig |
int | lastLogFrames = 0 |
ros::Time | lastLogTime |
boost::scoped_ptr< ros::Publisher > | leftImagePublisher |
double | maxDepth |
PointCloudColorMode | pointCloudColorMode |
sensor_msgs::PointCloud2Ptr | pointCloudMsg |
boost::scoped_ptr< Reconstruct3D > | recon3d |
std::string | remoteHost |
std::string | remotePort |
boost::scoped_ptr< ros::Publisher > | rightImagePublisher |
bool | rosCoordinateSystem |
bool | rosTimestamps |
boost::scoped_ptr< SceneScanParameters > | sceneScanParameters |
bool | useQFromCalibFile |
bool | useTcp |
Definition at line 61 of file nerian_stereo_node_base.h.
|
private |
Enumerator | |
---|---|
RGB_SEPARATE | |
RGB_COMBINED | |
INTENSITY | |
NONE |
Definition at line 90 of file nerian_stereo_node_base.h.
|
inline |
Definition at line 63 of file nerian_stereo_node_base.h.
|
inline |
Definition at line 66 of file nerian_stereo_node_base.h.
|
private |
Auto-generated code to check for parameter changes and forward them to the device.
|
private |
Auto-generated code to override the dynamic_reconfigure limits and defaults for all parameters.
|
private |
Auto-generated code to set initial parameters according to those obtained from the device.
|
private |
Copies all points in a point cloud that have a depth smaller than maxDepth. Other points are set to NaN.
Definition at line 467 of file nerian_stereo_node_base.cpp.
|
private |
Copies the intensity or RGB data to the point cloud.
Definition at line 378 of file nerian_stereo_node_base.cpp.
|
private |
Definition at line 19 of file nerian_stereo_node_base.cpp.
|
privatepure virtual |
Implemented in nerian_stereo::StereoNode, and nerian_stereo::StereoNodelet.
|
privatepure virtual |
Implemented in nerian_stereo::StereoNode, and nerian_stereo::StereoNodelet.
void nerian_stereo::StereoNodeBase::init | ( | ) |
Performs general initializations.
Definition at line 76 of file nerian_stereo_node_base.cpp.
void nerian_stereo::StereoNodeBase::initDynamicReconfigure | ( | ) |
Definition at line 44 of file nerian_stereo_node_base.cpp.
|
private |
Performs all neccessary initializations for point cloud+ publishing.
Definition at line 483 of file nerian_stereo_node_base.cpp.
|
private |
Loads a camera calibration file if configured.
Definition at line 216 of file nerian_stereo_node_base.cpp.
void nerian_stereo::StereoNodeBase::prepareAsyncTransfer | ( | ) |
Connects to the image service to request the stream of image pairs.
Definition at line 159 of file nerian_stereo_node_base.cpp.
void nerian_stereo::StereoNodeBase::processOneImagePair | ( | ) |
Definition at line 165 of file nerian_stereo_node_base.cpp.
|
private |
Publishes the camera info once per second.
Definition at line 553 of file nerian_stereo_node_base.cpp.
|
private |
Publishes the disparity map as 16-bit grayscale image or color coded RGB image.
Definition at line 235 of file nerian_stereo_node_base.cpp.
|
private |
Reconstructs the 3D locations form the disparity map and publishes them as point cloud.
Definition at line 298 of file nerian_stereo_node_base.cpp.
|
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 284 of file nerian_stereo_node_base.cpp.
|
private |
Reads a vector from the calibration file to a boost:array.
Definition at line 626 of file nerian_stereo_node_base.cpp.
|
private |
Definition at line 38 of file nerian_stereo_node_base.cpp.
|
private |
Definition at line 31 of file nerian_stereo_node_base.cpp.
|
private |
Definition at line 140 of file nerian_stereo_node_base.h.
|
private |
Definition at line 124 of file nerian_stereo_node_base.h.
|
private |
Definition at line 136 of file nerian_stereo_node_base.h.
|
private |
Definition at line 105 of file nerian_stereo_node_base.h.
|
private |
Definition at line 137 of file nerian_stereo_node_base.h.
|
private |
Definition at line 101 of file nerian_stereo_node_base.h.
|
private |
Definition at line 133 of file nerian_stereo_node_base.h.
|
private |
Definition at line 134 of file nerian_stereo_node_base.h.
|
private |
Definition at line 117 of file nerian_stereo_node_base.h.
|
private |
Definition at line 118 of file nerian_stereo_node_base.h.
|
private |
Definition at line 102 of file nerian_stereo_node_base.h.
|
private |
Definition at line 108 of file nerian_stereo_node_base.h.
|
private |
Definition at line 125 of file nerian_stereo_node_base.h.
|
private |
Definition at line 122 of file nerian_stereo_node_base.h.
|
private |
Definition at line 131 of file nerian_stereo_node_base.h.
|
private |
Definition at line 110 of file nerian_stereo_node_base.h.
|
private |
Definition at line 138 of file nerian_stereo_node_base.h.
|
private |
Definition at line 109 of file nerian_stereo_node_base.h.
|
private |
Definition at line 142 of file nerian_stereo_node_base.h.
|
private |
Definition at line 141 of file nerian_stereo_node_base.h.
|
private |
Definition at line 103 of file nerian_stereo_node_base.h.
|
private |
Definition at line 126 of file nerian_stereo_node_base.h.
|
private |
Definition at line 128 of file nerian_stereo_node_base.h.
|
private |
Definition at line 135 of file nerian_stereo_node_base.h.
|
private |
Definition at line 132 of file nerian_stereo_node_base.h.
|
private |
Definition at line 123 of file nerian_stereo_node_base.h.
|
private |
Definition at line 121 of file nerian_stereo_node_base.h.
|
private |
Definition at line 104 of file nerian_stereo_node_base.h.
|
private |
Definition at line 119 of file nerian_stereo_node_base.h.
|
private |
Definition at line 120 of file nerian_stereo_node_base.h.
|
private |
Definition at line 113 of file nerian_stereo_node_base.h.
|
private |
Definition at line 127 of file nerian_stereo_node_base.h.
|
private |
Definition at line 116 of file nerian_stereo_node_base.h.