MRPT  1.9.9
laser_scan.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 #include <geometry_msgs/Pose.h>
13 #include <mrpt/obs/obs_frwds.h>
14 #include <mrpt/poses/poses_frwds.h>
15 #include <sensor_msgs/LaserScan.h>
16 #include <cstdint>
17 #include <string>
18 
19 namespace mrpt::ros1bridge
20 {
21 /** \addtogroup mrpt_ros1bridge_grp
22  * @{ */
23 
24 /** ROS->MRPT: Takes a sensor_msgs::LaserScan and the relative pose of the laser
25  * wrt base_link and builds a CObservation2DRangeScan
26  * \return true on sucessful conversion, false on any error.
27  * \sa toROS
28  */
29 bool fromROS(
30  const sensor_msgs::LaserScan& msg, const mrpt::poses::CPose3D& pose,
32 
33 /** MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in
34  * sensor_msgs::LaserScan
35  * \return true on sucessful conversion, false on any error.
36  * \sa fromROS
37  */
38 bool toROS(
39  const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::LaserScan& msg);
40 
41 /** MRPT->ROS: Takes a CObservation2DRangeScan and outputs range data in
42  * sensor_msgs::LaserScan + the relative pose of the laser wrt base_link
43  * \return true on sucessful conversion, false on any error.
44  * \sa fromROS
45  */
46 bool toROS(
47  const mrpt::obs::CObservation2DRangeScan& obj, sensor_msgs::LaserScan& msg,
48  geometry_msgs::Pose& pose);
49 
50 /** @} */
51 
52 } // namespace mrpt::ros1bridge
bool 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" fie...
Definition: gps.cpp:48
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
ROS message: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html MRPT message: https://github...
Definition: gps.h:28
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:85
bool fromROS(const sensor_msgs::NavSatFix &msg, mrpt::obs::CObservationGPS &obj)
Convert sensor_msgs/NavSatFix -> mrpt::obs::CObservationGPS.
Definition: gps.cpp:20



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: c7a3bec24 Sun Mar 29 18:33:13 2020 +0200 at dom mar 29 18:50:38 CEST 2020