MRPT  2.0.2
Classes | Namespaces | Functions
[mrpt-ros1bridge]

Detailed Description

Conversion between MRPT and ROS 1 types.

Library `mrpt-ros1bridge`

[New in MRPT 2.0.0]

This C++ library is part of MRPT and can be installed in Debian-based systems with:

    sudo apt install libmrpt-ros1bridge-dev

See: Using MRPT from your CMake project

Classes

class  mrpt::ros1bridge::MapHdl
 Methods to convert between ROS msgs and MRPT objects for map datatypes. More...
 

Namespaces

 mrpt::ros1bridge
 ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github.com/MRPT/mrpt/blob/master/libs/obs/include/mrpt/obs/CObservationGPS.h.
 

Functions

bool mrpt::ros1bridge::fromROS (const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
 Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservationGPS &obj, const std_msgs::Header &msg_header, sensor_msgs::NavSatFix &msg)
 Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes. More...
 
mrpt::img::CImage mrpt::ros1bridge::fromROS (const sensor_msgs::Image &i)
 Makes a deep copy of the image data. More...
 
sensor_msgs::Image mrpt::ros1bridge::toROS (const mrpt::img::CImage &i, const std_msgs::Header &msg_header)
 Makes a deep copy of the image data. More...
 
bool mrpt::ros1bridge::fromROS (const sensor_msgs::Imu &msg, mrpt::obs::CObservationIMU &obj)
 Convert sensor_msgs/Imu -> mrpt::obs::CObservationIMU // STILL NEED TO WRITE CODE FOR COVARIANCE. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservationIMU &obj, const std_msgs::Header &msg_header, sensor_msgs::Imu &msg)
 Convert mrpt::obs::CObservationIMU -> sensor_msgs/Imu The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes. More...
 
bool mrpt::ros1bridge::fromROS (const sensor_msgs::LaserScan &msg, const mrpt::poses::CPose3D &pose, mrpt::obs::CObservation2DRangeScan &obj)
 ROS->MRPT: Takes a sensor_msgs::LaserScan and the relative pose of the laser wrt base_link and builds a CObservation2DRangeScan. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservation2DRangeScan &obj, sensor_msgs::LaserScan &msg)
 MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::LaserScan. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservation2DRangeScan &obj, sensor_msgs::LaserScan &msg, geometry_msgs::Pose &pose)
 MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::LaserScan + the relative pose of the laser wrt base_link. More...
 
tf2::Matrix3x3 mrpt::ros1bridge::toROS (const mrpt::math::CMatrixDouble33 &src)
 
tf2::Transform mrpt::ros1bridge::toROS_tfTransform (const mrpt::poses::CPose2D &src)
 
geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose (const mrpt::poses::CPose2D &src)
 
tf2::Transform mrpt::ros1bridge::toROS_tfTransform (const mrpt::math::TPose2D &src)
 
geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose (const mrpt::math::TPose2D &src)
 
tf2::Transform mrpt::ros1bridge::toROS_tfTransform (const mrpt::poses::CPose3D &src)
 
geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose (const mrpt::poses::CPose3D &src)
 
tf2::Transform mrpt::ros1bridge::toROS_tfTransform (const mrpt::math::TPose3D &src)
 
geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose (const mrpt::math::TPose3D &src)
 
geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS_Pose (const mrpt::poses::CPose3DPDFGaussian &src)
 
geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS (const mrpt::poses::CPose3DPDFGaussianInf &src)
 
geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS (const mrpt::poses::CPosePDFGaussian &src)
 
geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS (const mrpt::poses::CPosePDFGaussianInf &src)
 
geometry_msgs::Quaternion mrpt::ros1bridge::toROS (const mrpt::math::CQuaternionDouble &src)
 
mrpt::poses::CPose3D mrpt::ros1bridge::fromROS (const tf2::Transform &src)
 
mrpt::math::CMatrixDouble33 mrpt::ros1bridge::fromROS (const tf2::Matrix3x3 &src)
 
mrpt::poses::CPose3D mrpt::ros1bridge::fromROS (const geometry_msgs::Pose &src)
 
mrpt::poses::CPose3DPDFGaussian mrpt::ros1bridge::fromROS (const geometry_msgs::PoseWithCovariance &src)
 
mrpt::math::CQuaternionDouble mrpt::ros1bridge::fromROS (const geometry_msgs::Quaternion &src)
 
bool mrpt::ros1bridge::fromROS (const sensor_msgs::Range &msg, mrpt::obs::CObservationRange &obj)
 Convert sensor_msgs/Range -> mrpt::obs::CObservationRange. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservationRange &obj, const std_msgs::Header &msg_header, sensor_msgs::Range *msg)
 Convert mrpt::obs::CObservationRange -> sensor_msgs/Range The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::obs::CObservationStereoImages &obj, const std_msgs::Header &msg_header, sensor_msgs::Image &left, sensor_msgs::Image &right, stereo_msgs::DisparityImage &disparity)
 
mrpt::system::TTimeStamp mrpt::ros1bridge::fromROS (const ros::Time &src)
 converts ros time to mrpt time More...
 
ros::Time mrpt::ros1bridge::toROS (const mrpt::system::TTimeStamp &src)
 converts mrpt time to ros time More...
 

Maps, Occupancy Grid Maps: ROS <-> MRPT

bool mrpt::ros1bridge::fromROS (const nav_msgs::OccupancyGrid &src, mrpt::maps::COccupancyGridMap2D &des)
 converts ros msg to mrpt object More...
 
bool mrpt::ros1bridge::toROS (const mrpt::maps::COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg, const std_msgs::Header &header)
 converts mrpt object to ros msg and updates the msg header More...
 
bool mrpt::ros1bridge::toROS (const mrpt::maps::COccupancyGridMap2D &src, nav_msgs::OccupancyGrid &msg)
 converts mrpt object to ros msg More...
 

Point clouds: ROS <-> MRPT

bool mrpt::ros1bridge::fromROS (const sensor_msgs::PointCloud &msg, mrpt::maps::CSimplePointsMap &obj)
 Convert sensor_msgs/PointCloud -> mrpt::maps::CSimplePointsMap CSimplePointsMap only contains (x,y,z) data, so sensor_msgs::PointCloud::channels are ignored. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::maps::CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud &msg)
 Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes. More...
 

sensor_msgs::PointCloud2: ROS <-> MRPT

bool mrpt::ros1bridge::fromROS (const sensor_msgs::PointCloud2 &msg, mrpt::maps::CSimplePointsMap &obj)
 Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap Only (x,y,z) data is converted. More...
 
bool mrpt::ros1bridge::fromROS (const sensor_msgs::PointCloud2 &msg, mrpt::maps::CPointsMapXYZI &obj)
 
bool mrpt::ros1bridge::fromROS (const sensor_msgs::PointCloud2 &m, mrpt::obs::CObservationRotatingScan &o, const mrpt::poses::CPose3D &sensorPoseOnRobot, unsigned int num_azimuth_divisions=360)
 Convert sensor_msgs/PointCloud2 -> mrpt::obs::CObservationRotatingScan. More...
 
std::set< std::string > mrpt::ros1bridge::extractFields (const sensor_msgs::PointCloud2 &msg)
 Extract a list of fields found in the point cloud. More...
 
bool mrpt::ros1bridge::toROS (const mrpt::maps::CSimplePointsMap &obj, const std_msgs::Header &msg_header, sensor_msgs::PointCloud2 &msg)
 Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2 The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes. More...
 

Function Documentation

◆ extractFields()

std::set< std::string > mrpt::ros1bridge::extractFields ( const sensor_msgs::PointCloud2 &  msg)

Extract a list of fields found in the point cloud.

Typically: {"x","y","z","intensity"}

Definition at line 73 of file point_cloud2.cpp.

◆ fromROS() [1/16]

mrpt::system::TTimeStamp mrpt::ros1bridge::fromROS ( const ros::Time &  src)

converts ros time to mrpt time

Parameters
srcros time
desmrpt time

Definition at line 16 of file time.cpp.

References mrpt::system::time_tToTimestamp().

Here is the call graph for this function:

◆ fromROS() [2/16]

mrpt::img::CImage mrpt::ros1bridge::fromROS ( const sensor_msgs::Image &  i)

Makes a deep copy of the image data.

Definition at line 29 of file image.cpp.

References mrpt::img::DEEP_COPY.

◆ fromROS() [3/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::LaserScan &  msg,
const mrpt::poses::CPose3D pose,
mrpt::obs::CObservation2DRangeScan obj 
)

ROS->MRPT: Takes a sensor_msgs::LaserScan and the relative pose of the laser wrt base_link and builds a CObservation2DRangeScan.

Returns
true on sucessful conversion, false on any error.
See also
toROS

◆ fromROS() [4/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::PointCloud &  msg,
mrpt::maps::CSimplePointsMap obj 
)

Convert sensor_msgs/PointCloud -> mrpt::maps::CSimplePointsMap CSimplePointsMap only contains (x,y,z) data, so sensor_msgs::PointCloud::channels are ignored.

Returns
true on sucessful conversion, false on any error.
See also
toROS

Definition at line 17 of file point_cloud.cpp.

References mrpt::maps::CMetricMap::clear(), mrpt::maps::CPointsMap::insertPoint(), and mrpt::maps::CSimplePointsMap::reserve().

Here is the call graph for this function:

◆ fromROS() [5/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::Range &  msg,
mrpt::obs::CObservationRange obj 
)

Convert sensor_msgs/Range -> mrpt::obs::CObservationRange.

Returns
true on sucessful conversion, false on any error.

again this is amibiguous as can't be certain of number of measurement from corresponding ROS message

again this is amibiguous as can't be certain of number of measurement from corresponding ROS message

Definition at line 20 of file range.cpp.

References mrpt::obs::CObservationRange::maxSensorDistance, mrpt::obs::CObservationRange::minSensorDistance, mrpt::obs::CObservationRange::sensedData, and mrpt::obs::CObservationRange::sensorConeApperture.

◆ fromROS() [6/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::PointCloud2 &  msg,
mrpt::maps::CSimplePointsMap obj 
)

Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap Only (x,y,z) data is converted.

Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap.

To use the intensity channel, see the alternative signature for CPointsMapXYZI. Requires point cloud fields: x,y,z.

Returns
true on sucessful conversion, false on any error.
See also
toROS
Returns
true on sucessful conversion, false on any error.

Definition at line 84 of file point_cloud2.cpp.

References mrpt::ros1bridge::check_field(), mrpt::maps::CMetricMap::clear(), mrpt::ros1bridge::get_float_from_field(), mrpt::maps::CPointsMap::insertPoint(), and mrpt::maps::CSimplePointsMap::reserve().

Here is the call graph for this function:

◆ fromROS() [7/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::Imu &  msg,
mrpt::obs::CObservationIMU obj 
)

Convert sensor_msgs/Imu -> mrpt::obs::CObservationIMU // STILL NEED TO WRITE CODE FOR COVARIANCE.

Returns
true on sucessful conversion, false on any error.

Definition at line 20 of file imu.cpp.

References mrpt::obs::IMU_ORI_QUAT_W, mrpt::obs::IMU_ORI_QUAT_X, mrpt::obs::IMU_ORI_QUAT_Y, mrpt::obs::IMU_ORI_QUAT_Z, mrpt::obs::IMU_WX, mrpt::obs::IMU_WY, mrpt::obs::IMU_WZ, mrpt::obs::IMU_X_ACC, mrpt::obs::IMU_Y_ACC, mrpt::obs::IMU_Z_ACC, and mrpt::obs::CObservationIMU::set().

Here is the call graph for this function:

◆ fromROS() [8/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::NavSatFix &  msg,
mrpt::obs::CObservationGPS obj 
)

Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.

Returns
true on sucessful conversion, false on any error.

Definition at line 20 of file gps.cpp.

References mrpt::obs::gnss::Message_NMEA_GGA::content_t::altitude_meters, mrpt::obs::gnss::Message_NMEA_GGA::fields, mrpt::obs::gnss::Message_NMEA_GGA::content_t::fix_quality, mrpt::obs::gnss::Message_NMEA_GGA::content_t::latitude_degrees, mrpt::obs::gnss::Message_NMEA_GGA::content_t::longitude_degrees, and mrpt::obs::CObservationGPS::setMsg().

Referenced by check_CPose3D_tofrom_ROS(), mrpt::ros1bridge::convert(), mrpt::ros1bridge::fromROS(), and TEST().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fromROS() [9/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::PointCloud2 &  msg,
mrpt::maps::CPointsMapXYZI obj 
)

Definition at line 123 of file point_cloud2.cpp.

References mrpt::ros1bridge::check_field(), mrpt::maps::CMetricMap::clear(), mrpt::ros1bridge::get_float_from_field(), mrpt::maps::CPointsMap::insertPoint(), mrpt::maps::CPointsMapXYZI::reserve(), mrpt::maps::CPointsMapXYZI::setPointIntensity(), and mrpt::maps::CPointsMap::size().

Here is the call graph for this function:

◆ fromROS() [10/16]

bool mrpt::ros1bridge::fromROS ( const sensor_msgs::PointCloud2 &  m,
mrpt::obs::CObservationRotatingScan o,
const mrpt::poses::CPose3D sensorPoseOnRobot,
unsigned int  num_azimuth_divisions = 360 
)

◆ fromROS() [11/16]

mrpt::poses::CPose3D mrpt::ros1bridge::fromROS ( const tf2::Transform &  src)

Definition at line 221 of file pose.cpp.

References mrpt::ros1bridge::fromROS(), mrpt::poses::CPose3D::setRotationMatrix(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().

Here is the call graph for this function:

◆ fromROS() [12/16]

mrpt::math::CMatrixDouble33 mrpt::ros1bridge::fromROS ( const tf2::Matrix3x3 &  src)

Definition at line 231 of file pose.cpp.

◆ fromROS() [13/16]

mrpt::poses::CPose3D mrpt::ros1bridge::fromROS ( const geometry_msgs::Pose &  src)

Definition at line 239 of file pose.cpp.

References mrpt::math::CQuaternion< T >::x().

Here is the call graph for this function:

◆ fromROS() [14/16]

mrpt::poses::CPose3DPDFGaussian mrpt::ros1bridge::fromROS ( const geometry_msgs::PoseWithCovariance &  src)

Definition at line 248 of file pose.cpp.

References mrpt::poses::CPose3DPDFGaussian::cov, mrpt::ros1bridge::fromROS(), and mrpt::poses::CPose3DPDFGaussian::mean.

Here is the call graph for this function:

◆ fromROS() [15/16]

mrpt::math::CQuaternionDouble mrpt::ros1bridge::fromROS ( const geometry_msgs::Quaternion &  src)

Definition at line 264 of file pose.cpp.

References mrpt::math::CQuaternion< T >::r(), mrpt::math::CQuaternion< T >::x(), mrpt::math::CQuaternion< T >::y(), and mrpt::math::CQuaternion< T >::z().

Here is the call graph for this function:

◆ fromROS() [16/16]

bool mrpt::ros1bridge::fromROS ( const nav_msgs::OccupancyGrid &  src,
mrpt::maps::COccupancyGridMap2D des 
)

converts ros msg to mrpt object

Returns
true on sucessful conversion, false on any error.
Parameters
src
des

Definition at line 84 of file map.cpp.

References mrpt::maps::COccupancyGridMap2D::getRow(), MRPT_END, MRPT_START, and mrpt::maps::COccupancyGridMap2D::setSize().

Here is the call graph for this function:

◆ toROS() [1/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservationStereoImages obj,
const std_msgs::Header &  msg_header,
sensor_msgs::Image &  left,
sensor_msgs::Image &  right,
stereo_msgs::DisparityImage &  disparity 
)

◆ toROS() [2/17]

tf2::Matrix3x3 mrpt::ros1bridge::toROS ( const mrpt::math::CMatrixDouble33 src)

Definition at line 41 of file pose.cpp.

◆ toROS() [3/17]

ros::Time mrpt::ros1bridge::toROS ( const mrpt::system::TTimeStamp src)

converts mrpt time to ros time

Parameters
srcros time
desmrpt time

Definition at line 30 of file time.cpp.

References mrpt::system::timestampTotime_t().

Here is the call graph for this function:

◆ toROS() [4/17]

sensor_msgs::Image mrpt::ros1bridge::toROS ( const mrpt::img::CImage i,
const std_msgs::Header &  msg_header 
)

Makes a deep copy of the image data.

Definition at line 35 of file image.cpp.

References mrpt::img::CImage::asCvMatRef(), mrpt::img::CImage::getHeight(), and mrpt::img::CImage::getWidth().

Here is the call graph for this function:

◆ toROS() [5/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservation2DRangeScan obj,
sensor_msgs::LaserScan &  msg 
)

MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::LaserScan.

Returns
true on sucessful conversion, false on any error.
See also
fromROS

Definition at line 63 of file laser_scan.cpp.

References mrpt::obs::CObservation2DRangeScan::aperture, mrpt::obs::CObservation2DRangeScan::getScanRange(), mrpt::obs::CObservation2DRangeScan::getScanSize(), mrpt::obs::CObservation2DRangeScan::maxRange, mrpt::obs::CObservation::sensorLabel, mrpt::obs::CObservation::timestamp, and mrpt::ros1bridge::toROS().

Here is the call graph for this function:

◆ toROS() [6/17]

bool mrpt::ros1bridge::toROS ( const mrpt::maps::CSimplePointsMap obj,
const std_msgs::Header &  msg_header,
sensor_msgs::PointCloud &  msg 
)

Convert mrpt::maps::CSimplePointsMap -> sensor_msgs/PointCloud The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud::channels will be empty.

Returns
true on sucessful conversion, false on any error.
See also
fromROS

Definition at line 29 of file point_cloud.cpp.

References mrpt::maps::CPointsMap::getPoint(), and mrpt::maps::CPointsMap::size().

Here is the call graph for this function:

◆ toROS() [7/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservationRange obj,
const std_msgs::Header &  msg_header,
sensor_msgs::Range *  msg 
)

Convert mrpt::obs::CObservationRange -> sensor_msgs/Range The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since COnservation does not contain "radiation_type", sensor_msgs::Range::radiation_type will be empty.

Returns
true on sucessful conversion, false on any error.

following part needs to be double checked, it looks incorrect ROS has single number float for range, MRPT has a list of sensedDistances
currently the following are not available in MRPT for corresponding range ROS message NO corresponding value for MRPT radiation_type at http://mrpt.ual.es/reference/devel/_c_observation_range_8h_source.html

following part needs to be double checked, it looks incorrect ROS has single number float for range, MRPT has a list of sensedDistances
currently the following are not available in MRPT for corresponding range ROS message NO corresponding value for MRPT radiation_type at http://mrpt.ual.es/reference/devel/_c_observation_range_8h_source.html

Definition at line 32 of file range.cpp.

References mrpt::obs::gnss::header, mrpt::obs::CObservationRange::maxSensorDistance, mrpt::obs::CObservationRange::minSensorDistance, mrpt::obs::CObservationRange::sensedData, and mrpt::obs::CObservationRange::sensorConeApperture.

◆ toROS() [8/17]

geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS ( const mrpt::poses::CPose3DPDFGaussianInf src)

Definition at line 154 of file pose.cpp.

References mrpt::poses::CPose3DPDFGaussian::copyFrom(), and mrpt::ros1bridge::toROS_Pose().

Here is the call graph for this function:

◆ toROS() [9/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservationIMU obj,
const std_msgs::Header &  msg_header,
sensor_msgs::Imu &  msg 
)

Convert mrpt::obs::CObservationIMU -> sensor_msgs/Imu The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since COnservationIMU does not contain covariance terms NEED TO fix those.

Returns
true on sucessful conversion, false on any error.

computing acceleration in global navigation frame not in local vehicle frame, might be the other way round

computing acceleration in global navigation frame not in local vehicle frame, might be the other way round

Definition at line 41 of file imu.cpp.

References mrpt::obs::IMU_ORI_QUAT_W, mrpt::obs::IMU_ORI_QUAT_X, mrpt::obs::IMU_ORI_QUAT_Y, mrpt::obs::IMU_ORI_QUAT_Z, mrpt::obs::IMU_WX, mrpt::obs::IMU_WY, mrpt::obs::IMU_WZ, mrpt::obs::IMU_X_ACC, mrpt::obs::IMU_Y_ACC, mrpt::obs::IMU_Z_ACC, and mrpt::obs::CObservationIMU::rawMeasurements.

◆ toROS() [10/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservation2DRangeScan obj,
sensor_msgs::LaserScan &  msg,
geometry_msgs::Pose &  pose 
)

MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in sensor_msgs::LaserScan + the relative pose of the laser wrt base_link.

Returns
true on sucessful conversion, false on any error.
See also
fromROS

Definition at line 90 of file laser_scan.cpp.

References mrpt::obs::CObservation2DRangeScan::sensorPose, mrpt::ros1bridge::toROS(), and mrpt::ros1bridge::toROS_Pose().

Here is the call graph for this function:

◆ toROS() [11/17]

bool mrpt::ros1bridge::toROS ( const mrpt::obs::CObservationGPS obj,
const std_msgs::Header &  msg_header,
sensor_msgs::NavSatFix &  msg 
)

Convert mrpt::obs::CObservationGPS -> sensor_msgs/NavSatFix The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since COnservationGPS does not contain "position_covariance" and "position_covariance_type" sensor_msgs::NavSatFix::position_covariance_type and sensor_msgs::NavSatFix::position_covariance will be empty.

Returns
true on sucessful conversion, false on any error.

following parameter assigned as per http://mrpt.ual.es/reference/devel/structmrpt_1_1obs_1_1gnss_1_1_message___n_m_e_a___g_g_a_1_1content__t.html#a33415dc947663d43015605c41b0f66cb http://mrpt.ual.es/reference/devel/gnss__messages__ascii__nmea_8h_source.html
position_covariance is not available in mrpt position_covariance type is not available in mrpt

following parameter assigned as per http://mrpt.ual.es/reference/devel/structmrpt_1_1obs_1_1gnss_1_1_message___n_m_e_a___g_g_a_1_1content__t.html#a33415dc947663d43015605c41b0f66cb http://mrpt.ual.es/reference/devel/gnss__messages__ascii__nmea_8h_source.html
position_covariance is not available in mrpt position_covariance type is not available in mrpt

Definition at line 48 of file gps.cpp.

References mrpt::obs::gnss::Message_NMEA_GGA::content_t::altitude_meters, mrpt::obs::gnss::Message_NMEA_GGA::fields, mrpt::obs::gnss::Message_NMEA_GGA::content_t::fix_quality, mrpt::obs::CObservationGPS::getMsgByClass(), mrpt::obs::CObservationGPS::hasMsgClass(), mrpt::obs::gnss::Message_NMEA_GGA::content_t::latitude_degrees, and mrpt::obs::gnss::Message_NMEA_GGA::content_t::longitude_degrees.

Referenced by TEST(), mrpt::ros1bridge::toROS(), and mrpt::ros1bridge::toROS_tfTransform().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ toROS() [12/17]

geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS ( const mrpt::poses::CPosePDFGaussian src)

Definition at line 162 of file pose.cpp.

References mrpt::poses::CPosePDFGaussian::cov, mrpt::poses::CPosePDFGaussian::mean, and mrpt::ros1bridge::toROS_Pose().

Here is the call graph for this function:

◆ toROS() [13/17]

geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS ( const mrpt::poses::CPosePDFGaussianInf src)

Definition at line 197 of file pose.cpp.

References mrpt::poses::CPosePDFGaussian::copyFrom(), and mrpt::ros1bridge::toROS().

Here is the call graph for this function:

◆ toROS() [14/17]

geometry_msgs::Quaternion mrpt::ros1bridge::toROS ( const mrpt::math::CQuaternionDouble src)

Definition at line 206 of file pose.cpp.

References mrpt::math::CQuaternion< T >::r(), mrpt::math::CQuaternion< T >::x(), mrpt::math::CQuaternion< T >::y(), and mrpt::math::CQuaternion< T >::z().

Here is the call graph for this function:

◆ toROS() [15/17]

bool mrpt::ros1bridge::toROS ( const mrpt::maps::CSimplePointsMap obj,
const std_msgs::Header &  msg_header,
sensor_msgs::PointCloud2 &  msg 
)

Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2 The user must supply the "msg_header" field to be copied into the output message object, since that part does not appear in MRPT classes.

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud2::channels will be empty.

Returns
true on sucessful conversion, false on any error.
See also
fromROS

Since CSimplePointsMap only contains (x,y,z) data, sensor_msgs::PointCloud2::channels will be empty.

Returns
true on sucessful conversion, false on any error.

Definition at line 174 of file point_cloud2.cpp.

◆ toROS() [16/17]

bool mrpt::ros1bridge::toROS ( const mrpt::maps::COccupancyGridMap2D src,
nav_msgs::OccupancyGrid &  msg,
const std_msgs::Header &  header 
)

converts mrpt object to ros msg and updates the msg header

Returns
true on sucessful conversion, false on any error.
Parameters
src
header

Definition at line 112 of file map.cpp.

References mrpt::obs::gnss::header, and mrpt::ros1bridge::toROS().

Here is the call graph for this function:

◆ toROS() [17/17]

bool mrpt::ros1bridge::toROS ( const mrpt::maps::COccupancyGridMap2D src,
nav_msgs::OccupancyGrid &  msg 
)

converts mrpt object to ros msg

Returns
true on sucessful conversion, false on any error.

Definition at line 120 of file map.cpp.

References mrpt::maps::COccupancyGridMap2D::getResolution(), mrpt::maps::COccupancyGridMap2D::getRow(), mrpt::maps::COccupancyGridMap2D::getSizeX(), mrpt::maps::COccupancyGridMap2D::getSizeY(), mrpt::maps::COccupancyGridMap2D::getXMin(), and mrpt::maps::COccupancyGridMap2D::getYMin().

Here is the call graph for this function:

◆ toROS_Pose() [1/5]

geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose ( const mrpt::poses::CPose2D src)

Definition at line 54 of file pose.cpp.

Referenced by check_CPose3D_tofrom_ROS(), TEST(), mrpt::ros1bridge::toROS(), and mrpt::ros1bridge::toROS_Pose().

Here is the caller graph for this function:

◆ toROS_Pose() [2/5]

geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose ( const mrpt::math::TPose2D src)

Definition at line 64 of file pose.cpp.

References mrpt::math::TPose2D::phi, mrpt::math::TPose2D::x, and mrpt::math::TPose2D::y.

◆ toROS_Pose() [3/5]

geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose ( const mrpt::poses::CPose3D src)

Definition at line 101 of file pose.cpp.

References mrpt::poses::CPose3D::getAsQuaternion(), mrpt::math::CQuaternion< T >::r(), mrpt::math::CQuaternion< T >::x(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), mrpt::math::CQuaternion< T >::y(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y(), and mrpt::math::CQuaternion< T >::z().

Here is the call graph for this function:

◆ toROS_Pose() [4/5]

geometry_msgs::Pose mrpt::ros1bridge::toROS_Pose ( const mrpt::math::TPose3D src)

Definition at line 124 of file pose.cpp.

References mrpt::ros1bridge::toROS_Pose().

Here is the call graph for this function:

◆ toROS_Pose() [5/5]

geometry_msgs::PoseWithCovariance mrpt::ros1bridge::toROS_Pose ( const mrpt::poses::CPose3DPDFGaussian src)

Definition at line 129 of file pose.cpp.

References mrpt::poses::CPose3DPDFGaussian::cov, mrpt::poses::CPose3DPDFGaussian::mean, and mrpt::ros1bridge::toROS_Pose().

Here is the call graph for this function:

◆ toROS_tfTransform() [1/4]

tf2::Transform mrpt::ros1bridge::toROS_tfTransform ( const mrpt::poses::CPose2D src)

Definition at line 49 of file pose.cpp.

Referenced by mrpt::ros1bridge::toROS_tfTransform().

Here is the caller graph for this function:

◆ toROS_tfTransform() [2/4]

tf2::Transform mrpt::ros1bridge::toROS_tfTransform ( const mrpt::math::TPose2D src)

Definition at line 59 of file pose.cpp.

References mrpt::ros1bridge::toROS_tfTransform().

Here is the call graph for this function:

◆ toROS_tfTransform() [3/4]

tf2::Transform mrpt::ros1bridge::toROS_tfTransform ( const mrpt::poses::CPose3D src)

Definition at line 93 of file pose.cpp.

References mrpt::poses::CPose3D::getRotationMatrix(), mrpt::ros1bridge::toROS(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y().

Here is the call graph for this function:

◆ toROS_tfTransform() [4/4]

tf2::Transform mrpt::ros1bridge::toROS_tfTransform ( const mrpt::math::TPose3D src)

Definition at line 119 of file pose.cpp.

References mrpt::ros1bridge::toROS_tfTransform().

Here is the call graph for this function:



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020