#include <nerian_stereo_node_base.h>
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::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 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::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 |
geometry_msgs::TransformStamped | currentTransform |
boost::scoped_ptr< DataChannelService > | dataChannelService |
boost::scoped_ptr< DeviceParameters > | deviceParameters |
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 |
std::string | internalFrame |
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< tf2_ros::TransformBroadcaster > | transformBroadcaster |
bool | useQFromCalibFile |
bool | useTcp |
Definition at line 72 of file nerian_stereo_node_base.h.
|
private |
Enumerator | |
---|---|
RGB_SEPARATE | |
RGB_COMBINED | |
INTENSITY | |
NONE |
Definition at line 116 of file nerian_stereo_node_base.h.
|
inline |
Definition at line 74 of file nerian_stereo_node_base.h.
|
inline |
Definition at line 77 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 520 of file nerian_stereo_node_base.cpp.
|
private |
Copies the intensity or RGB data to the point cloud.
Definition at line 431 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::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.
|
private |
Performs all neccessary initializations for point cloud+ publishing.
Definition at line 536 of file nerian_stereo_node_base.cpp.
|
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.
|
private |
Publishes the camera info once per second.
Definition at line 606 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 260 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 348 of file nerian_stereo_node_base.cpp.
void nerian_stereo::StereoNodeBase::publishTransform | ( | ) |
Definition at line 740 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 334 of file nerian_stereo_node_base.cpp.
|
private |
Reads a vector from the calibration file to a boost:array.
Definition at line 679 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 169 of file nerian_stereo_node_base.h.
|
private |
Definition at line 153 of file nerian_stereo_node_base.h.
|
private |
Definition at line 165 of file nerian_stereo_node_base.h.
|
private |
Definition at line 131 of file nerian_stereo_node_base.h.
|
private |
Definition at line 166 of file nerian_stereo_node_base.h.
|
private |
Definition at line 127 of file nerian_stereo_node_base.h.
|
private |
Definition at line 162 of file nerian_stereo_node_base.h.
|
private |
Definition at line 163 of file nerian_stereo_node_base.h.
|
private |
Definition at line 145 of file nerian_stereo_node_base.h.
|
private |
Definition at line 146 of file nerian_stereo_node_base.h.
|
private |
Definition at line 176 of file nerian_stereo_node_base.h.
|
private |
Definition at line 174 of file nerian_stereo_node_base.h.
|
private |
Definition at line 141 of file nerian_stereo_node_base.h.
|
private |
Definition at line 128 of file nerian_stereo_node_base.h.
|
private |
Definition at line 136 of file nerian_stereo_node_base.h.
|
private |
Definition at line 154 of file nerian_stereo_node_base.h.
|
private |
Definition at line 150 of file nerian_stereo_node_base.h.
|
private |
Definition at line 160 of file nerian_stereo_node_base.h.
|
private |
Definition at line 138 of file nerian_stereo_node_base.h.
|
private |
Definition at line 151 of file nerian_stereo_node_base.h.
|
private |
Definition at line 167 of file nerian_stereo_node_base.h.
|
private |
Definition at line 137 of file nerian_stereo_node_base.h.
|
private |
Definition at line 171 of file nerian_stereo_node_base.h.
|
private |
Definition at line 170 of file nerian_stereo_node_base.h.
|
private |
Definition at line 129 of file nerian_stereo_node_base.h.
|
private |
Definition at line 155 of file nerian_stereo_node_base.h.
|
private |
Definition at line 157 of file nerian_stereo_node_base.h.
|
private |
Definition at line 164 of file nerian_stereo_node_base.h.
|
private |
Definition at line 161 of file nerian_stereo_node_base.h.
|
private |
Definition at line 152 of file nerian_stereo_node_base.h.
|
private |
Definition at line 149 of file nerian_stereo_node_base.h.
|
private |
Definition at line 130 of file nerian_stereo_node_base.h.
|
private |
Definition at line 147 of file nerian_stereo_node_base.h.
|
private |
Definition at line 148 of file nerian_stereo_node_base.h.
|
private |
Definition at line 133 of file nerian_stereo_node_base.h.
|
private |
Definition at line 156 of file nerian_stereo_node_base.h.
|
private |
Definition at line 144 of file nerian_stereo_node_base.h.