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

void initPointCloud (ros::NodeHandle &privateNh)
 Performs all neccessary initializations for point cloud+ publishing.
void publishCameraInfo (ros::Time stamp)
 Publishes the camera info once per second.
void publishDispMapMsg (int width, int height, int stride, unsigned char *data, ros::Time stamp)
 Publishes the disparity map as 16-bit grayscale image or color coded RGB image.
void publishImageMsg (int width, int height, int stride, unsigned char *data, ros::Time stamp)
 Publishes a rectified left camera image.
void publishPointCloudMsg (int width, int height, int leftStride, int dispStride, unsigned char *leftData, unsigned char *dispData, ros::Time stamp)
 Reconstructs the 3D locations form the disparity map and publishes them as point cloud.
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
bool dispWindow
std::string frame
int frameNum
std::string host
boost::scoped_ptr< ros::PublisherimagePublisher
bool intensityChannel
ros::Time lastCamInfoPublish
ros::NodeHandle nh
sensor_msgs::PointCloud2Ptr pointCloudMsg
std::string port
boost::scoped_ptr< Reconstruct3D > recon3d
bool rosCoordinateSystem
bool useTcp
boost::scoped_ptr< SDLWindow > window

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 50 of file nerian_sp1_node.cpp.


Constructor & Destructor Documentation

Sp1Node::Sp1Node ( ) [inline]

Definition at line 52 of file nerian_sp1_node.cpp.

Sp1Node::~Sp1Node ( ) [inline]

Definition at line 55 of file nerian_sp1_node.cpp.


Member Function Documentation

void Sp1Node::init ( ) [inline]

Performs general initializations.

Definition at line 61 of file nerian_sp1_node.cpp.

void Sp1Node::initPointCloud ( ros::NodeHandle privateNh) [inline, private]

Performs all neccessary initializations for point cloud+ publishing.

Definition at line 382 of file nerian_sp1_node.cpp.

void Sp1Node::publishCameraInfo ( ros::Time  stamp) [inline, private]

Publishes the camera info once per second.

Definition at line 446 of file nerian_sp1_node.cpp.

void Sp1Node::publishDispMapMsg ( int  width,
int  height,
int  stride,
unsigned char *  data,
ros::Time  stamp 
) [inline, private]

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

Definition at line 267 of file nerian_sp1_node.cpp.

void Sp1Node::publishImageMsg ( int  width,
int  height,
int  stride,
unsigned char *  data,
ros::Time  stamp 
) [inline, private]

Publishes a rectified left camera image.

Definition at line 250 of file nerian_sp1_node.cpp.

void Sp1Node::publishPointCloudMsg ( int  width,
int  height,
int  leftStride,
int  dispStride,
unsigned char *  leftData,
unsigned char *  dispData,
ros::Time  stamp 
) [inline, private]

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

Definition at line 317 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 513 of file nerian_sp1_node.cpp.

int Sp1Node::run ( ) [inline]

The main loop of this node.

Definition at line 136 of file nerian_sp1_node.cpp.


Member Data Documentation

std::string Sp1Node::calibFile [private]

Definition at line 233 of file nerian_sp1_node.cpp.

cv::FileStorage Sp1Node::calibStorage [private]

Definition at line 242 of file nerian_sp1_node.cpp.

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

Definition at line 222 of file nerian_sp1_node.cpp.

nerian_sp1::StereoCameraInfoPtr Sp1Node::camInfoMsg [private]

Definition at line 243 of file nerian_sp1_node.cpp.

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

Definition at line 219 of file nerian_sp1_node.cpp.

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

Definition at line 239 of file nerian_sp1_node.cpp.

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

Definition at line 240 of file nerian_sp1_node.cpp.

bool Sp1Node::colorCodeDispMap [private]

Definition at line 227 of file nerian_sp1_node.cpp.

bool Sp1Node::colorCodeLegend [private]

Definition at line 228 of file nerian_sp1_node.cpp.

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

Definition at line 220 of file nerian_sp1_node.cpp.

bool Sp1Node::dispWindow [private]

Definition at line 234 of file nerian_sp1_node.cpp.

std::string Sp1Node::frame [private]

Definition at line 231 of file nerian_sp1_node.cpp.

int Sp1Node::frameNum [private]

Definition at line 237 of file nerian_sp1_node.cpp.

std::string Sp1Node::host [private]

Definition at line 232 of file nerian_sp1_node.cpp.

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

Definition at line 221 of file nerian_sp1_node.cpp.

bool Sp1Node::intensityChannel [private]

Definition at line 225 of file nerian_sp1_node.cpp.

Definition at line 244 of file nerian_sp1_node.cpp.

Definition at line 218 of file nerian_sp1_node.cpp.

sensor_msgs::PointCloud2Ptr Sp1Node::pointCloudMsg [private]

Definition at line 241 of file nerian_sp1_node.cpp.

std::string Sp1Node::port [private]

Definition at line 230 of file nerian_sp1_node.cpp.

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

Definition at line 238 of file nerian_sp1_node.cpp.

Definition at line 229 of file nerian_sp1_node.cpp.

bool Sp1Node::useTcp [private]

Definition at line 226 of file nerian_sp1_node.cpp.

boost::scoped_ptr<SDLWindow> Sp1Node::window [private]

Definition at line 245 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 Wed Sep 16 2015 06:40:29