$search

sensor_msgs Namespace Reference

Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. More...

Namespaces

namespace  distortion_models
namespace  image_encodings
namespace  msg
namespace  srv

Classes

struct  CameraInfo_
struct  ChannelFloat32_
struct  CompressedImage_
struct  Image_
struct  Imu_
struct  JointState_
struct  Joy_
struct  JoyFeedback_
struct  JoyFeedbackArray_
struct  LaserScan_
struct  NavSatFix_
struct  NavSatStatus_
struct  PointCloud2_
struct  PointCloud_
struct  PointField_
struct  Range_
struct  RegionOfInterest_
struct  SetCameraInfo
struct  SetCameraInfoRequest_
struct  SetCameraInfoResponse_

Typedefs

typedef
::sensor_msgs::CameraInfo_
< std::allocator< void > > 
CameraInfo
typedef boost::shared_ptr
< ::sensor_msgs::CameraInfo
const > 
CameraInfoConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::CameraInfo
CameraInfoPtr
typedef
::sensor_msgs::ChannelFloat32_
< std::allocator< void > > 
ChannelFloat32
typedef boost::shared_ptr
< ::sensor_msgs::ChannelFloat32
const > 
ChannelFloat32ConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::ChannelFloat32
ChannelFloat32Ptr
typedef
::sensor_msgs::CompressedImage_
< std::allocator< void > > 
CompressedImage
typedef boost::shared_ptr
< ::sensor_msgs::CompressedImage
const > 
CompressedImageConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::CompressedImage
CompressedImagePtr
typedef ::sensor_msgs::Image_
< std::allocator< void > > 
Image
typedef boost::shared_ptr
< ::sensor_msgs::Image const > 
ImageConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::Image
ImagePtr
typedef ::sensor_msgs::Imu_
< std::allocator< void > > 
Imu
typedef boost::shared_ptr
< ::sensor_msgs::Imu const > 
ImuConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::Imu
ImuPtr
typedef
::sensor_msgs::JointState_
< std::allocator< void > > 
JointState
typedef boost::shared_ptr
< ::sensor_msgs::JointState
const > 
JointStateConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::JointState
JointStatePtr
typedef ::sensor_msgs::Joy_
< std::allocator< void > > 
Joy
typedef boost::shared_ptr
< ::sensor_msgs::Joy const > 
JoyConstPtr
typedef
::sensor_msgs::JoyFeedback_
< std::allocator< void > > 
JoyFeedback
typedef
::sensor_msgs::JoyFeedbackArray_
< std::allocator< void > > 
JoyFeedbackArray
typedef boost::shared_ptr
< ::sensor_msgs::JoyFeedbackArray
const > 
JoyFeedbackArrayConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::JoyFeedbackArray
JoyFeedbackArrayPtr
typedef boost::shared_ptr
< ::sensor_msgs::JoyFeedback
const > 
JoyFeedbackConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::JoyFeedback
JoyFeedbackPtr
typedef boost::shared_ptr
< ::sensor_msgs::Joy
JoyPtr
typedef
::sensor_msgs::LaserScan_
< std::allocator< void > > 
LaserScan
typedef boost::shared_ptr
< ::sensor_msgs::LaserScan
const > 
LaserScanConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::LaserScan
LaserScanPtr
typedef
::sensor_msgs::NavSatFix_
< std::allocator< void > > 
NavSatFix
typedef boost::shared_ptr
< ::sensor_msgs::NavSatFix
const > 
NavSatFixConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::NavSatFix
NavSatFixPtr
typedef
::sensor_msgs::NavSatStatus_
< std::allocator< void > > 
NavSatStatus
typedef boost::shared_ptr
< ::sensor_msgs::NavSatStatus
const > 
NavSatStatusConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::NavSatStatus
NavSatStatusPtr
typedef
::sensor_msgs::PointCloud_
< std::allocator< void > > 
PointCloud
typedef
::sensor_msgs::PointCloud2_
< std::allocator< void > > 
PointCloud2
typedef boost::shared_ptr
< ::sensor_msgs::PointCloud2
const > 
PointCloud2ConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::PointCloud2
PointCloud2Ptr
typedef boost::shared_ptr
< ::sensor_msgs::PointCloud
const > 
PointCloudConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::PointCloud
PointCloudPtr
typedef
::sensor_msgs::PointField_
< std::allocator< void > > 
PointField
typedef boost::shared_ptr
< ::sensor_msgs::PointField
const > 
PointFieldConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::PointField
PointFieldPtr
typedef ::sensor_msgs::Range_
< std::allocator< void > > 
Range
typedef boost::shared_ptr
< ::sensor_msgs::Range const > 
RangeConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::Range
RangePtr
typedef
::sensor_msgs::RegionOfInterest_
< std::allocator< void > > 
RegionOfInterest
typedef boost::shared_ptr
< ::sensor_msgs::RegionOfInterest
const > 
RegionOfInterestConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::RegionOfInterest
RegionOfInterestPtr
typedef
::sensor_msgs::SetCameraInfoRequest_
< std::allocator< void > > 
SetCameraInfoRequest
typedef boost::shared_ptr
< ::sensor_msgs::SetCameraInfoRequest
const > 
SetCameraInfoRequestConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::SetCameraInfoRequest
SetCameraInfoRequestPtr
typedef
::sensor_msgs::SetCameraInfoResponse_
< std::allocator< void > > 
SetCameraInfoResponse
typedef boost::shared_ptr
< ::sensor_msgs::SetCameraInfoResponse
const > 
SetCameraInfoResponseConstPtr
typedef boost::shared_ptr
< ::sensor_msgs::SetCameraInfoResponse
SetCameraInfoResponsePtr

Functions

void clearImage (Image &image)
bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
 Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
 Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
bool fillImage (Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
 Get the index of a specified field (i.e., dimension/channel).
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::RegionOfInterest_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::Range_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::PointField_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::PointCloud2_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::PointCloud_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::NavSatStatus_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::NavSatFix_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::LaserScan_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::JoyFeedbackArray_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::JoyFeedback_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::Joy_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::JointState_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::Imu_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::Image_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::CompressedImage_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::ChannelFloat32_< ContainerAllocator > &v)
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::sensor_msgs::CameraInfo_< ContainerAllocator > &v)

Detailed Description

Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format.

Author:
Radu Bogdan Rusu

Typedef Documentation

typedef ::sensor_msgs::CameraInfo_<std::allocator<void> > sensor_msgs::CameraInfo

Definition at line 351 of file CameraInfo.h.

typedef boost::shared_ptr< ::sensor_msgs::CameraInfo const> sensor_msgs::CameraInfoConstPtr

Definition at line 354 of file CameraInfo.h.

typedef boost::shared_ptr< ::sensor_msgs::CameraInfo> sensor_msgs::CameraInfoPtr

Definition at line 353 of file CameraInfo.h.

Definition at line 121 of file ChannelFloat32.h.

Definition at line 124 of file ChannelFloat32.h.

Definition at line 123 of file ChannelFloat32.h.

Definition at line 137 of file CompressedImage.h.

Definition at line 140 of file CompressedImage.h.

Definition at line 139 of file CompressedImage.h.

typedef ::sensor_msgs::Image_<std::allocator<void> > sensor_msgs::Image

Definition at line 183 of file Image.h.

typedef boost::shared_ptr< ::sensor_msgs::Image const> sensor_msgs::ImageConstPtr

Definition at line 186 of file Image.h.

typedef boost::shared_ptr< ::sensor_msgs::Image> sensor_msgs::ImagePtr

Definition at line 185 of file Image.h.

typedef ::sensor_msgs::Imu_<std::allocator<void> > sensor_msgs::Imu

Definition at line 200 of file Imu.h.

typedef boost::shared_ptr< ::sensor_msgs::Imu const> sensor_msgs::ImuConstPtr

Definition at line 203 of file Imu.h.

typedef boost::shared_ptr< ::sensor_msgs::Imu> sensor_msgs::ImuPtr

Definition at line 202 of file Imu.h.

typedef ::sensor_msgs::JointState_<std::allocator<void> > sensor_msgs::JointState

Definition at line 178 of file JointState.h.

typedef boost::shared_ptr< ::sensor_msgs::JointState const> sensor_msgs::JointStateConstPtr

Definition at line 181 of file JointState.h.

typedef boost::shared_ptr< ::sensor_msgs::JointState> sensor_msgs::JointStatePtr

Definition at line 180 of file JointState.h.

typedef ::sensor_msgs::Joy_<std::allocator<void> > sensor_msgs::Joy

Definition at line 132 of file Joy.h.

typedef boost::shared_ptr< ::sensor_msgs::Joy const> sensor_msgs::JoyConstPtr

Definition at line 135 of file Joy.h.

typedef ::sensor_msgs::JoyFeedback_<std::allocator<void> > sensor_msgs::JoyFeedback

Definition at line 119 of file JoyFeedback.h.

Definition at line 109 of file JoyFeedbackArray.h.

Definition at line 112 of file JoyFeedbackArray.h.

Definition at line 111 of file JoyFeedbackArray.h.

typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback const> sensor_msgs::JoyFeedbackConstPtr

Definition at line 122 of file JoyFeedback.h.

Definition at line 121 of file JoyFeedback.h.

typedef boost::shared_ptr< ::sensor_msgs::Joy> sensor_msgs::JoyPtr

Definition at line 134 of file Joy.h.

typedef ::sensor_msgs::LaserScan_<std::allocator<void> > sensor_msgs::LaserScan

Definition at line 213 of file LaserScan.h.

typedef boost::shared_ptr< ::sensor_msgs::LaserScan const> sensor_msgs::LaserScanConstPtr

Definition at line 216 of file LaserScan.h.

typedef boost::shared_ptr< ::sensor_msgs::LaserScan> sensor_msgs::LaserScanPtr

Definition at line 215 of file LaserScan.h.

typedef ::sensor_msgs::NavSatFix_<std::allocator<void> > sensor_msgs::NavSatFix

Definition at line 223 of file NavSatFix.h.

typedef boost::shared_ptr< ::sensor_msgs::NavSatFix const> sensor_msgs::NavSatFixConstPtr

Definition at line 226 of file NavSatFix.h.

typedef boost::shared_ptr< ::sensor_msgs::NavSatFix> sensor_msgs::NavSatFixPtr

Definition at line 225 of file NavSatFix.h.

typedef ::sensor_msgs::NavSatStatus_<std::allocator<void> > sensor_msgs::NavSatStatus

Definition at line 123 of file NavSatStatus.h.

typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus const> sensor_msgs::NavSatStatusConstPtr

Definition at line 126 of file NavSatStatus.h.

Definition at line 125 of file NavSatStatus.h.

typedef ::sensor_msgs::PointCloud_<std::allocator<void> > sensor_msgs::PointCloud

Definition at line 184 of file PointCloud.h.

typedef ::sensor_msgs::PointCloud2_<std::allocator<void> > sensor_msgs::PointCloud2

Definition at line 222 of file PointCloud2.h.

typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> sensor_msgs::PointCloud2ConstPtr

Definition at line 225 of file PointCloud2.h.

Definition at line 224 of file PointCloud2.h.

typedef boost::shared_ptr< ::sensor_msgs::PointCloud const> sensor_msgs::PointCloudConstPtr

Definition at line 187 of file PointCloud.h.

typedef boost::shared_ptr< ::sensor_msgs::PointCloud> sensor_msgs::PointCloudPtr

Definition at line 186 of file PointCloud.h.

typedef ::sensor_msgs::PointField_<std::allocator<void> > sensor_msgs::PointField

Definition at line 132 of file PointField.h.

typedef boost::shared_ptr< ::sensor_msgs::PointField const> sensor_msgs::PointFieldConstPtr

Definition at line 135 of file PointField.h.

typedef boost::shared_ptr< ::sensor_msgs::PointField> sensor_msgs::PointFieldPtr

Definition at line 134 of file PointField.h.

typedef ::sensor_msgs::Range_<std::allocator<void> > sensor_msgs::Range

Definition at line 176 of file Range.h.

typedef boost::shared_ptr< ::sensor_msgs::Range const> sensor_msgs::RangeConstPtr

Definition at line 179 of file Range.h.

typedef boost::shared_ptr< ::sensor_msgs::Range> sensor_msgs::RangePtr

Definition at line 178 of file Range.h.

Definition at line 136 of file RegionOfInterest.h.

Definition at line 139 of file RegionOfInterest.h.

Definition at line 138 of file RegionOfInterest.h.

Definition at line 280 of file SetCameraInfo.h.

Definition at line 283 of file SetCameraInfo.h.

Definition at line 282 of file SetCameraInfo.h.

Definition at line 369 of file SetCameraInfo.h.

Definition at line 372 of file SetCameraInfo.h.

Definition at line 371 of file SetCameraInfo.h.


Function Documentation

void sensor_msgs::clearImage ( Image &  image  ) 

Definition at line 63 of file fill_image.h.

bool sensor_msgs::convertPointCloud2ToPointCloud ( const sensor_msgs::PointCloud2 input,
sensor_msgs::PointCloud output 
)

Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.

Parameters:
input the message in the sensor_msgs::PointCloud2 format
output the resultant message in the sensor_msgs::PointCloud format

Definition at line 96 of file point_cloud_conversion.cpp.

bool sensor_msgs::convertPointCloudToPointCloud2 ( const sensor_msgs::PointCloud input,
sensor_msgs::PointCloud2 output 
)

Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.

Parameters:
input the message in the sensor_msgs::PointCloud format
output the resultant message in the sensor_msgs::PointCloud2 format

Definition at line 53 of file point_cloud_conversion.cpp.

bool sensor_msgs::fillImage ( Image &  image,
const std::string &  encoding_arg,
uint32_t  rows_arg,
uint32_t  cols_arg,
uint32_t  step_arg,
const void *  data_arg 
)

Definition at line 44 of file fill_image.h.

int sensor_msgs::getPointCloud2FieldIndex ( const sensor_msgs::PointCloud2 cloud,
const std::string &  field_name 
)

Get the index of a specified field (i.e., dimension/channel).

Parameters:
points the the point cloud message
field_name the string defining the field name

Definition at line 42 of file point_cloud_conversion.cpp.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::RegionOfInterest_< ContainerAllocator > &  v 
) [inline]

Definition at line 143 of file RegionOfInterest.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::Range_< ContainerAllocator > &  v 
) [inline]

Definition at line 183 of file Range.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::PointField_< ContainerAllocator > &  v 
) [inline]

Definition at line 139 of file PointField.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::PointCloud2_< ContainerAllocator > &  v 
) [inline]

Definition at line 229 of file PointCloud2.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::PointCloud_< ContainerAllocator > &  v 
) [inline]

Definition at line 191 of file PointCloud.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::NavSatStatus_< ContainerAllocator > &  v 
) [inline]

Definition at line 130 of file NavSatStatus.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::NavSatFix_< ContainerAllocator > &  v 
) [inline]

Definition at line 230 of file NavSatFix.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::LaserScan_< ContainerAllocator > &  v 
) [inline]

Definition at line 220 of file LaserScan.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::JoyFeedbackArray_< ContainerAllocator > &  v 
) [inline]

Definition at line 116 of file JoyFeedbackArray.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::JoyFeedback_< ContainerAllocator > &  v 
) [inline]

Definition at line 126 of file JoyFeedback.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::Joy_< ContainerAllocator > &  v 
) [inline]

Definition at line 139 of file Joy.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::JointState_< ContainerAllocator > &  v 
) [inline]

Definition at line 185 of file JointState.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::Imu_< ContainerAllocator > &  v 
) [inline]

Definition at line 207 of file Imu.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::Image_< ContainerAllocator > &  v 
) [inline]

Definition at line 190 of file Image.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::CompressedImage_< ContainerAllocator > &  v 
) [inline]

Definition at line 144 of file CompressedImage.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::ChannelFloat32_< ContainerAllocator > &  v 
) [inline]

Definition at line 128 of file ChannelFloat32.h.

template<typename ContainerAllocator >
std::ostream& sensor_msgs::operator<< ( std::ostream &  s,
const ::sensor_msgs::CameraInfo_< ContainerAllocator > &  v 
) [inline]

Definition at line 358 of file CameraInfo.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


sensor_msgs
Author(s): Maintained by Tully Foote/tfoote@willowgarage.com
autogenerated on Fri Mar 1 15:06:14 2013