Public Member Functions | Private Member Functions | Private Attributes
Sp1Node Class Reference

A simple node that receives data from the SP1 stereo vision system and forwards it to ROS. More...

List of all members.

Public Member Functions

void init ()
 Performs general initializations.
int run ()
 The main loop of this node.
 Sp1Node ()
 ~Sp1Node ()

Private Member Functions

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.
void initPointCloud ()
 Performs all neccessary initializations for point cloud+ publishing.
void loadCameraCalibration ()
 Loads a camera calibration file if configured.
void publishCameraInfo (ros::Time stamp, const ImagePair &imagePair)
 Publishes the camera info once per second.
void publishDispMapMsg (const ImagePair &imagePair, ros::Time stamp)
 Publishes the disparity map as 16-bit grayscale image or color coded RGB image.
void publishImageMsg (const ImagePair &imagePair, ros::Time stamp)
 Publishes a rectified left camera image.
void publishPointCloudMsg (ImagePair &imagePair, ros::Time stamp)
 Reconstructs the 3D locations form the disparity map and publishes them as point cloud.
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.
template<class T >
void readCalibrationArray (const char *key, T &dest)
 Reads a vector from the calibration file to a boost:array.

Private Attributes

std::string calibFile
cv::FileStorage calibStorage
boost::scoped_ptr< ros::PublishercameraInfoPublisher
nerian_sp1::StereoCameraInfoPtr camInfoMsg
boost::scoped_ptr< ros::PublishercloudPublisher
boost::scoped_ptr< ColorCoder > colCoder
cv::Mat_< cv::Vec3b > colDispMap
bool colorCodeDispMap
bool colorCodeLegend
boost::scoped_ptr< ros::PublisherdisparityPublisher
double execDelay
std::string frame
int frameNum
bool intensityChannel
ros::Time lastCamInfoPublish
boost::scoped_ptr< ros::PublisherleftImagePublisher
std::string localHost
std::string localPort
double maxDepth
ros::NodeHandle nh
sensor_msgs::PointCloud2Ptr pointCloudMsg
boost::scoped_ptr< Reconstruct3D > recon3d
std::string remoteHost
std::string remotePort
boost::scoped_ptr< ros::PublisherrightImagePublisher
bool rosCoordinateSystem
bool useTcp

Detailed Description

A simple node that receives data from the SP1 stereo vision system and forwards it to ROS.

The SP1 stereo vision system is a stand-alone device for real-time stereo matching. It transmits its processing results through gigagibt ethernet which are then received by this node. The node converts the received data into ROS messages, which contain the following data:

In addition, camera calibration information are also published. For configuration parameters, please see the provided example launch file. For more information about the SP1 stereo vision system, please visit http://nerian.com/products/sp1-stereo-vision/

Definition at line 49 of file nerian_sp1_node.cpp.


Constructor & Destructor Documentation

Sp1Node::Sp1Node ( ) [inline]

Definition at line 51 of file nerian_sp1_node.cpp.

Sp1Node::~Sp1Node ( ) [inline]

Definition at line 54 of file nerian_sp1_node.cpp.


Member Function Documentation

template<int coord>
void Sp1Node::copyPointCloudClamped ( float *  src,
float *  dst,
int  size 
) [inline, private]

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

Definition at line 425 of file nerian_sp1_node.cpp.

void Sp1Node::init ( ) [inline]

Performs general initializations.

Definition at line 60 of file nerian_sp1_node.cpp.

void Sp1Node::initPointCloud ( ) [inline, private]

Performs all neccessary initializations for point cloud+ publishing.

Definition at line 445 of file nerian_sp1_node.cpp.

void Sp1Node::loadCameraCalibration ( ) [inline, private]

Loads a camera calibration file if configured.

Definition at line 231 of file nerian_sp1_node.cpp.

void Sp1Node::publishCameraInfo ( ros::Time  stamp,
const ImagePair &  imagePair 
) [inline, private]

Publishes the camera info once per second.

Definition at line 489 of file nerian_sp1_node.cpp.

void Sp1Node::publishDispMapMsg ( const ImagePair &  imagePair,
ros::Time  stamp 
) [inline, private]

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

Definition at line 272 of file nerian_sp1_node.cpp.

void Sp1Node::publishImageMsg ( const ImagePair &  imagePair,
ros::Time  stamp 
) [inline, private]

Publishes a rectified left camera image.

Definition at line 253 of file nerian_sp1_node.cpp.

void Sp1Node::publishPointCloudMsg ( ImagePair &  imagePair,
ros::Time  stamp 
) [inline, private]

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

Definition at line 338 of file nerian_sp1_node.cpp.

void Sp1Node::qMatrixToRosCoords ( const float *  src,
float *  dst 
) [inline, 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 320 of file nerian_sp1_node.cpp.

template<class T >
void Sp1Node::readCalibrationArray ( const char *  key,
T dest 
) [inline, private]

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

Definition at line 566 of file nerian_sp1_node.cpp.

int Sp1Node::run ( ) [inline]

The main loop of this node.

Definition at line 138 of file nerian_sp1_node.cpp.


Member Data Documentation

std::string Sp1Node::calibFile [private]

Definition at line 214 of file nerian_sp1_node.cpp.

cv::FileStorage Sp1Node::calibStorage [private]

Definition at line 224 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ros::Publisher> Sp1Node::cameraInfoPublisher [private]

Definition at line 201 of file nerian_sp1_node.cpp.

nerian_sp1::StereoCameraInfoPtr Sp1Node::camInfoMsg [private]

Definition at line 225 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ros::Publisher> Sp1Node::cloudPublisher [private]

Definition at line 197 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ColorCoder> Sp1Node::colCoder [private]

Definition at line 221 of file nerian_sp1_node.cpp.

cv::Mat_<cv::Vec3b> Sp1Node::colDispMap [private]

Definition at line 222 of file nerian_sp1_node.cpp.

bool Sp1Node::colorCodeDispMap [private]

Definition at line 206 of file nerian_sp1_node.cpp.

bool Sp1Node::colorCodeLegend [private]

Definition at line 207 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ros::Publisher> Sp1Node::disparityPublisher [private]

Definition at line 198 of file nerian_sp1_node.cpp.

double Sp1Node::execDelay [private]

Definition at line 215 of file nerian_sp1_node.cpp.

std::string Sp1Node::frame [private]

Definition at line 211 of file nerian_sp1_node.cpp.

int Sp1Node::frameNum [private]

Definition at line 219 of file nerian_sp1_node.cpp.

bool Sp1Node::intensityChannel [private]

Definition at line 204 of file nerian_sp1_node.cpp.

Definition at line 226 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ros::Publisher> Sp1Node::leftImagePublisher [private]

Definition at line 199 of file nerian_sp1_node.cpp.

std::string Sp1Node::localHost [private]

Definition at line 213 of file nerian_sp1_node.cpp.

std::string Sp1Node::localPort [private]

Definition at line 210 of file nerian_sp1_node.cpp.

double Sp1Node::maxDepth [private]

Definition at line 216 of file nerian_sp1_node.cpp.

Definition at line 196 of file nerian_sp1_node.cpp.

sensor_msgs::PointCloud2Ptr Sp1Node::pointCloudMsg [private]

Definition at line 223 of file nerian_sp1_node.cpp.

boost::scoped_ptr<Reconstruct3D> Sp1Node::recon3d [private]

Definition at line 220 of file nerian_sp1_node.cpp.

std::string Sp1Node::remoteHost [private]

Definition at line 212 of file nerian_sp1_node.cpp.

std::string Sp1Node::remotePort [private]

Definition at line 209 of file nerian_sp1_node.cpp.

boost::scoped_ptr<ros::Publisher> Sp1Node::rightImagePublisher [private]

Definition at line 200 of file nerian_sp1_node.cpp.

Definition at line 208 of file nerian_sp1_node.cpp.

bool Sp1Node::useTcp [private]

Definition at line 205 of file nerian_sp1_node.cpp.


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


nerian_sp1
Author(s): Nerian Vision Technologies
autogenerated on Tue Oct 3 2017 03:03:12