Tools for manipulating sensor_msgs. More...
Namespaces | |
distortion_models | |
image_encodings | |
impl | |
Functions | |
static void | clearImage (Image &image) |
static bool | convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) |
Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message. More... | |
static bool | convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) |
Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. More... | |
static 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) |
static int | getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) |
Get the index of a specified field (i.e., dimension/channel) More... | |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::LaserEcho_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::SetCameraInfoRequest_< 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::SetCameraInfoResponse_< 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::Illuminance_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::Temperature_< 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::Joy_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::FluidPressure_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::TimeReference_< 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::MagneticField_< 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::RegionOfInterest_< 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::MultiDOFJointState_< 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::Image_< 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::Imu_< 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::NavSatFix_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::CameraInfo_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v) |
template<int point_field_type, typename T > | |
T | readPointCloud2BufferValue (const unsigned char *data_ptr) |
template<typename T > | |
T | readPointCloud2BufferValue (const unsigned char *data_ptr, const unsigned char datatype) |
template<int point_field_type, typename T > | |
void | writePointCloud2BufferValue (unsigned char *data_ptr, T value) |
template<typename T > | |
void | writePointCloud2BufferValue (unsigned char *data_ptr, const unsigned char datatype, T value) |
Tools for manipulating sensor_msgs.
This file provides a type to enum mapping for the different PointField types and methods to read and write in a PointCloud2 buffer for the different PointField types.
Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format.
This file provides two sets of utilities to modify and parse PointCloud2 The first set allows you to conveniently set the fields by hand:
#include <sensor_msgs/point_cloud_iterator.h> // Create a PointCloud2 sensor_msgs::PointCloud2 cloud_msg; // Fill some internals of the PoinCloud2 like the header/width/height ... cloud_msgs.height = 1; cloud_msgs.width = 4; // Set the point fields to xyzrgb and resize the vector with the following command // 4 is for the number of added fields. Each come in triplet: the name of the PointField, // the number of occurrences of the type in the PointField, the type of the PointField sensor_msgs::PointCloud2Modifier modifier(cloud_msg); modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32, "y", 1, sensor_msgs::PointField::FLOAT32, "z", 1, sensor_msgs::PointField::FLOAT32, "rgb", 1, sensor_msgs::PointField::FLOAT32); // For convenience and the xyz, rgb, rgba fields, you can also use the following overloaded function. // You have to be aware that the following function does add extra padding for backward compatibility though // so it is definitely the solution of choice for PointXYZ and PointXYZRGB // 2 is for the number of fields to add modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); // You can then reserve / resize as usual modifier.resize(100);
The second set allow you to traverse your PointCloud using an iterator:
// Define some raw data we'll put in the PointCloud2 float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0}; uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120}; // Define the iterators. When doing so, you define the Field you would like to iterate upon and // the type of you would like returned: it is not necessary the type of the PointField as sometimes // you pack data in another type (e.g. 3 uchar + 1 uchar for RGB are packed in a float) sensor_msgs::PointCloud2Iterator<float> iter_x(cloud_msg, "x"); sensor_msgs::PointCloud2Iterator<float> iter_y(cloud_msg, "y"); sensor_msgs::PointCloud2Iterator<float> iter_z(cloud_msg, "z"); // Even though the r,g,b,a fields do not exist (it's usually rgb, rgba), you can create iterators for // those: they will handle data packing for you (in little endian RGB is packed as *,R,G,B in a float // and RGBA as A,R,G,B) sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(cloud_msg, "r"); sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(cloud_msg, "g"); sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(cloud_msg, "b"); // Fill the PointCloud2 for(size_t i=0; i<n_points; ++i, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b) { *iter_x = point_data[3*i+0]; *iter_y = point_data[3*i+1]; *iter_z = point_data[3*i+2]; *iter_r = color_data[3*i+0]; *iter_g = color_data[3*i+1]; *iter_b = color_data[3*i+2]; }
typedef ::sensor_msgs::BatteryState_<std::allocator<void> > sensor_msgs::BatteryState |
Definition at line 134 of file BatteryState.h.
typedef boost::shared_ptr< ::sensor_msgs::BatteryState const> sensor_msgs::BatteryStateConstPtr |
Definition at line 137 of file BatteryState.h.
Definition at line 136 of file BatteryState.h.
typedef ::sensor_msgs::CameraInfo_<std::allocator<void> > sensor_msgs::CameraInfo |
Definition at line 110 of file CameraInfo.h.
typedef std::shared_ptr< ::sensor_msgs::CameraInfo const> sensor_msgs::CameraInfoConstPtr |
Definition at line 113 of file CameraInfo.h.
typedef std::shared_ptr< ::sensor_msgs::CameraInfo > sensor_msgs::CameraInfoPtr |
Definition at line 112 of file CameraInfo.h.
typedef ::sensor_msgs::ChannelFloat32_<std::allocator<void> > sensor_msgs::ChannelFloat32 |
Definition at line 52 of file ChannelFloat32.h.
typedef boost::shared_ptr< ::sensor_msgs::ChannelFloat32 const> sensor_msgs::ChannelFloat32ConstPtr |
Definition at line 55 of file ChannelFloat32.h.
Definition at line 54 of file ChannelFloat32.h.
typedef ::sensor_msgs::CompressedImage_<std::allocator<void> > sensor_msgs::CompressedImage |
Definition at line 58 of file CompressedImage.h.
typedef std::shared_ptr< ::sensor_msgs::CompressedImage const> sensor_msgs::CompressedImageConstPtr |
Definition at line 61 of file CompressedImage.h.
typedef std::shared_ptr< ::sensor_msgs::CompressedImage > sensor_msgs::CompressedImagePtr |
Definition at line 60 of file CompressedImage.h.
typedef ::sensor_msgs::FluidPressure_<std::allocator<void> > sensor_msgs::FluidPressure |
Definition at line 58 of file FluidPressure.h.
typedef boost::shared_ptr< ::sensor_msgs::FluidPressure const> sensor_msgs::FluidPressureConstPtr |
Definition at line 61 of file FluidPressure.h.
Definition at line 60 of file FluidPressure.h.
typedef ::sensor_msgs::Illuminance_<std::allocator<void> > sensor_msgs::Illuminance |
Definition at line 58 of file Illuminance.h.
typedef boost::shared_ptr< ::sensor_msgs::Illuminance const> sensor_msgs::IlluminanceConstPtr |
Definition at line 61 of file Illuminance.h.
Definition at line 60 of file Illuminance.h.
typedef ::sensor_msgs::Image_<std::allocator<void> > sensor_msgs::Image |
typedef std::shared_ptr< ::sensor_msgs::Image const> sensor_msgs::ImageConstPtr |
typedef std::shared_ptr< ::sensor_msgs::Image > sensor_msgs::ImagePtr |
typedef ::sensor_msgs::Imu_<std::allocator<void> > sensor_msgs::Imu |
typedef std::shared_ptr< ::sensor_msgs::Imu const> sensor_msgs::ImuConstPtr |
typedef std::shared_ptr< ::sensor_msgs::Imu > sensor_msgs::ImuPtr |
typedef ::sensor_msgs::JointState_<std::allocator<void> > sensor_msgs::JointState |
Definition at line 68 of file JointState.h.
typedef boost::shared_ptr< ::sensor_msgs::JointState const> sensor_msgs::JointStateConstPtr |
Definition at line 71 of file JointState.h.
Definition at line 70 of file JointState.h.
typedef ::sensor_msgs::Joy_<std::allocator<void> > sensor_msgs::Joy |
typedef boost::shared_ptr< ::sensor_msgs::Joy const> sensor_msgs::JoyConstPtr |
typedef ::sensor_msgs::JoyFeedback_<std::allocator<void> > sensor_msgs::JoyFeedback |
Definition at line 60 of file JoyFeedback.h.
typedef ::sensor_msgs::JoyFeedbackArray_<std::allocator<void> > sensor_msgs::JoyFeedbackArray |
Definition at line 48 of file JoyFeedbackArray.h.
typedef boost::shared_ptr< ::sensor_msgs::JoyFeedbackArray const> sensor_msgs::JoyFeedbackArrayConstPtr |
Definition at line 51 of file JoyFeedbackArray.h.
Definition at line 50 of file JoyFeedbackArray.h.
typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback const> sensor_msgs::JoyFeedbackConstPtr |
Definition at line 63 of file JoyFeedback.h.
Definition at line 62 of file JoyFeedback.h.
typedef boost::shared_ptr< ::sensor_msgs::Joy > sensor_msgs::JoyPtr |
typedef ::sensor_msgs::LaserEcho_<std::allocator<void> > sensor_msgs::LaserEcho |
Definition at line 47 of file LaserEcho.h.
typedef boost::shared_ptr< ::sensor_msgs::LaserEcho const> sensor_msgs::LaserEchoConstPtr |
Definition at line 50 of file LaserEcho.h.
Definition at line 49 of file LaserEcho.h.
typedef ::sensor_msgs::LaserScan_<std::allocator<void> > sensor_msgs::LaserScan |
Definition at line 93 of file LaserScan.h.
typedef boost::shared_ptr< ::sensor_msgs::LaserScan const> sensor_msgs::LaserScanConstPtr |
Definition at line 96 of file LaserScan.h.
Definition at line 95 of file LaserScan.h.
typedef ::sensor_msgs::MagneticField_<std::allocator<void> > sensor_msgs::MagneticField |
Definition at line 61 of file MagneticField.h.
typedef boost::shared_ptr< ::sensor_msgs::MagneticField const> sensor_msgs::MagneticFieldConstPtr |
Definition at line 64 of file MagneticField.h.
Definition at line 63 of file MagneticField.h.
typedef ::sensor_msgs::MultiDOFJointState_<std::allocator<void> > sensor_msgs::MultiDOFJointState |
Definition at line 71 of file MultiDOFJointState.h.
typedef boost::shared_ptr< ::sensor_msgs::MultiDOFJointState const> sensor_msgs::MultiDOFJointStateConstPtr |
Definition at line 74 of file MultiDOFJointState.h.
Definition at line 73 of file MultiDOFJointState.h.
typedef ::sensor_msgs::MultiEchoLaserScan_<std::allocator<void> > sensor_msgs::MultiEchoLaserScan |
Definition at line 95 of file MultiEchoLaserScan.h.
typedef boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan const> sensor_msgs::MultiEchoLaserScanConstPtr |
Definition at line 98 of file MultiEchoLaserScan.h.
Definition at line 97 of file MultiEchoLaserScan.h.
typedef ::sensor_msgs::NavSatFix_<std::allocator<void> > sensor_msgs::NavSatFix |
Definition at line 85 of file NavSatFix.h.
typedef boost::shared_ptr< ::sensor_msgs::NavSatFix const> sensor_msgs::NavSatFixConstPtr |
Definition at line 88 of file NavSatFix.h.
Definition at line 87 of file NavSatFix.h.
typedef ::sensor_msgs::NavSatStatus_<std::allocator<void> > sensor_msgs::NavSatStatus |
Definition at line 60 of file NavSatStatus.h.
typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus const> sensor_msgs::NavSatStatusConstPtr |
Definition at line 63 of file NavSatStatus.h.
Definition at line 62 of file NavSatStatus.h.
typedef ::sensor_msgs::PointCloud_<std::allocator<void> > sensor_msgs::PointCloud |
Definition at line 60 of file PointCloud.h.
typedef ::sensor_msgs::PointCloud2_<std::allocator<void> > sensor_msgs::PointCloud2 |
Definition at line 89 of file PointCloud2.h.
typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> sensor_msgs::PointCloud2ConstPtr |
Definition at line 92 of file PointCloud2.h.
Definition at line 91 of file PointCloud2.h.
typedef boost::shared_ptr< ::sensor_msgs::PointCloud const> sensor_msgs::PointCloudConstPtr |
Definition at line 63 of file PointCloud.h.
Definition at line 62 of file PointCloud.h.
typedef ::sensor_msgs::PointField_<std::allocator<void> > sensor_msgs::PointField |
Definition at line 70 of file PointField.h.
typedef boost::shared_ptr< ::sensor_msgs::PointField const> sensor_msgs::PointFieldConstPtr |
Definition at line 73 of file PointField.h.
Definition at line 72 of file PointField.h.
typedef ::sensor_msgs::Range_<std::allocator<void> > sensor_msgs::Range |
typedef boost::shared_ptr< ::sensor_msgs::Range const> sensor_msgs::RangeConstPtr |
typedef boost::shared_ptr< ::sensor_msgs::Range > sensor_msgs::RangePtr |
typedef ::sensor_msgs::RegionOfInterest_<std::allocator<void> > sensor_msgs::RegionOfInterest |
Definition at line 67 of file RegionOfInterest.h.
typedef std::shared_ptr< ::sensor_msgs::RegionOfInterest const> sensor_msgs::RegionOfInterestConstPtr |
Definition at line 70 of file RegionOfInterest.h.
typedef std::shared_ptr< ::sensor_msgs::RegionOfInterest > sensor_msgs::RegionOfInterestPtr |
Definition at line 69 of file RegionOfInterest.h.
typedef ::sensor_msgs::RelativeHumidity_<std::allocator<void> > sensor_msgs::RelativeHumidity |
Definition at line 58 of file RelativeHumidity.h.
typedef boost::shared_ptr< ::sensor_msgs::RelativeHumidity const> sensor_msgs::RelativeHumidityConstPtr |
Definition at line 61 of file RelativeHumidity.h.
Definition at line 60 of file RelativeHumidity.h.
typedef ::sensor_msgs::SetCameraInfoRequest_<std::allocator<void> > sensor_msgs::SetCameraInfoRequest |
Definition at line 48 of file SetCameraInfoRequest.h.
typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest const> sensor_msgs::SetCameraInfoRequestConstPtr |
Definition at line 51 of file SetCameraInfoRequest.h.
typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest > sensor_msgs::SetCameraInfoRequestPtr |
Definition at line 50 of file SetCameraInfoRequest.h.
typedef ::sensor_msgs::SetCameraInfoResponse_<std::allocator<void> > sensor_msgs::SetCameraInfoResponse |
Definition at line 52 of file SetCameraInfoResponse.h.
typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse const> sensor_msgs::SetCameraInfoResponseConstPtr |
Definition at line 55 of file SetCameraInfoResponse.h.
typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse > sensor_msgs::SetCameraInfoResponsePtr |
Definition at line 54 of file SetCameraInfoResponse.h.
typedef ::sensor_msgs::Temperature_<std::allocator<void> > sensor_msgs::Temperature |
Definition at line 58 of file Temperature.h.
typedef boost::shared_ptr< ::sensor_msgs::Temperature const> sensor_msgs::TemperatureConstPtr |
Definition at line 61 of file Temperature.h.
Definition at line 60 of file Temperature.h.
typedef ::sensor_msgs::TimeReference_<std::allocator<void> > sensor_msgs::TimeReference |
Definition at line 59 of file TimeReference.h.
typedef std::shared_ptr< ::sensor_msgs::TimeReference const> sensor_msgs::TimeReferenceConstPtr |
Definition at line 62 of file TimeReference.h.
typedef std::shared_ptr< ::sensor_msgs::TimeReference > sensor_msgs::TimeReferencePtr |
Definition at line 61 of file TimeReference.h.
Definition at line 63 of file fill_image.h.
|
inlinestatic |
Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message.
input | the message in the sensor_msgs::PointCloud2 format |
output | the resultant message in the sensor_msgs::PointCloud format |
Definition at line 117 of file point_cloud_conversion.h.
|
inlinestatic |
Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message.
input | the message in the sensor_msgs::PointCloud format |
output | the resultant message in the sensor_msgs::PointCloud2 format |
Definition at line 70 of file point_cloud_conversion.h.
|
inlinestatic |
Definition at line 44 of file fill_image.h.
|
inlinestatic |
Get the index of a specified field (i.e., dimension/channel)
points | the the point cloud message |
field_name | the string defining the field name |
Definition at line 56 of file point_cloud_conversion.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::LaserEcho_< ContainerAllocator > & | v | ||
) |
Definition at line 57 of file LaserEcho.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::SetCameraInfoRequest_< ContainerAllocator > & | v | ||
) |
Definition at line 58 of file SetCameraInfoRequest.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::JoyFeedbackArray_< ContainerAllocator > & | v | ||
) |
Definition at line 58 of file JoyFeedbackArray.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::SetCameraInfoResponse_< ContainerAllocator > & | v | ||
) |
Definition at line 62 of file SetCameraInfoResponse.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::ChannelFloat32_< ContainerAllocator > & | v | ||
) |
Definition at line 62 of file ChannelFloat32.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Illuminance_< ContainerAllocator > & | v | ||
) |
Definition at line 68 of file Illuminance.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::RelativeHumidity_< ContainerAllocator > & | v | ||
) |
Definition at line 68 of file RelativeHumidity.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Temperature_< ContainerAllocator > & | v | ||
) |
Definition at line 68 of file Temperature.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::CompressedImage_< ContainerAllocator > & | v | ||
) |
Definition at line 68 of file CompressedImage.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Joy_< ContainerAllocator > & | v | ||
) |
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::FluidPressure_< ContainerAllocator > & | v | ||
) |
Definition at line 68 of file FluidPressure.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::TimeReference_< ContainerAllocator > & | v | ||
) |
Definition at line 69 of file TimeReference.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::PointCloud_< ContainerAllocator > & | v | ||
) |
Definition at line 70 of file PointCloud.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::MagneticField_< ContainerAllocator > & | v | ||
) |
Definition at line 71 of file MagneticField.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::JoyFeedback_< ContainerAllocator > & | v | ||
) |
Definition at line 76 of file JoyFeedback.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::RegionOfInterest_< ContainerAllocator > & | v | ||
) |
Definition at line 77 of file RegionOfInterest.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::JointState_< ContainerAllocator > & | v | ||
) |
Definition at line 78 of file JointState.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::MultiDOFJointState_< ContainerAllocator > & | v | ||
) |
Definition at line 81 of file MultiDOFJointState.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::NavSatStatus_< ContainerAllocator > & | v | ||
) |
Definition at line 86 of file NavSatStatus.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Image_< ContainerAllocator > & | v | ||
) |
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Range_< ContainerAllocator > & | v | ||
) |
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::PointField_< ContainerAllocator > & | v | ||
) |
Definition at line 96 of file PointField.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::PointCloud2_< ContainerAllocator > & | v | ||
) |
Definition at line 99 of file PointCloud2.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::Imu_< ContainerAllocator > & | v | ||
) |
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::LaserScan_< ContainerAllocator > & | v | ||
) |
Definition at line 103 of file LaserScan.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::NavSatFix_< ContainerAllocator > & | v | ||
) |
Definition at line 103 of file NavSatFix.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > & | v | ||
) |
Definition at line 105 of file MultiEchoLaserScan.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::CameraInfo_< ContainerAllocator > & | v | ||
) |
Definition at line 120 of file CameraInfo.h.
std::ostream& sensor_msgs::operator<< | ( | std::ostream & | s, |
const ::sensor_msgs::BatteryState_< ContainerAllocator > & | v | ||
) |
Definition at line 186 of file BatteryState.h.
|
inline |
a value at the given pointer position, interpreted as the datatype specified by the given template argument point_field_type, to the given template type T and returns it.
data_ptr | pointer into the point cloud 2 buffer |
point_field_type | sensor_msgs::PointField datatype value |
T | return type |
Definition at line 91 of file point_field_conversion.h.
|
inline |
a value at the given pointer position interpreted as the datatype specified by the given datatype parameter to the given template type and returns it.
data_ptr | pointer into the point cloud 2 buffer |
datatype | sensor_msgs::PointField datatype value |
T | return type |
Definition at line 104 of file point_field_conversion.h.
|
inline |
a given value at the given point position interpreted as the datatype specified by the template argument point_field_type.
data_ptr | pointer into the point cloud 2 buffer |
value | the value to insert |
point_field_type | sensor_msgs::PointField datatype value |
T | type of the value to insert |
Definition at line 134 of file point_field_conversion.h.
|
inline |
a given value at the given point position interpreted as the datatype specified by the given datatype parameter.
data_ptr | pointer into the point cloud 2 buffer |
datatype | sensor_msgs::PointField datatype value |
value | the value to insert |
T | type of the value to insert |
Definition at line 148 of file point_field_conversion.h.