2D/3D points and poses
Overview
// enums enum mrpt::poses::TInterpolatorMethod; // classes template <class DERIVEDCLASS, std::size_t DIM> class mrpt::poses::CPoint; class mrpt::poses::CPoint2D; class mrpt::poses::CPoint3D; template <class DERIVEDCLASS, std::size_t DIM> class mrpt::poses::CPose; class mrpt::poses::CPose2D; class mrpt::poses::CPose3D; class mrpt::poses::CPose3DQuat; template <class DERIVEDCLASS, std::size_t DIM> class mrpt::poses::CPoseOrPoint; class mrpt::poses::CPoses2DSequence; class mrpt::poses::CPoses3DSequence; class mrpt::poses::CRobot2DPoseEstimator; template <int DIM> class mrpt::poses::FrameTransformer; template <int DIM> class mrpt::poses::FrameTransformerInterface; template <> class mrpt::poses::SE_average<2>; template <size_t DOF> class mrpt::poses::SE_average; template <> class mrpt::poses::SE_average<3>; template <size_t DOF> class mrpt::poses::SO_average; template <> class mrpt::poses::SO_average<3>; template <> class mrpt::poses::SO_average<2>; // global functions SensorToPoseMap mrpt::poses::sensor_poses_from_yaml(const mrpt::containers::yaml& d, const std::string& referenceFrame = "base_link"); SensorToPoseMap mrpt::poses::sensor_poses_from_yaml_file(const std::string& filename, const std::string& referenceFrame = "base_link");
Global Functions
SensorToPoseMap mrpt::poses::sensor_poses_from_yaml( const mrpt::containers::yaml& d, const std::string& referenceFrame = "base_link" )
Alternative to sensor_poses_from_yaml_file() where the yaml map inside sensors: ...
is directly passed programatically.
See also:
CPose3D, mrpt::obs::CObservation, sensor_poses_from_yaml_file()
SensorToPoseMap mrpt::poses::sensor_poses_from_yaml_file( const std::string& filename, const std::string& referenceFrame = "base_link" )
Utility to parse a YAML file with the extrinsic calibration of sensors.
Each YAML map entry defines a sensorLabel, and for each one an extrinsics
map containing the SE(3) relative pose between the parent
frame and this sensor. The pose is given as a quaternion and a translation.
The expected file contents is like:
* # My YAML file:
* sensors: # Note: sensor_poses_from_yaml() expects **this node** as input
* camera:
* extrinsics:
* quaternion: [qx, qy, qz, qw]
* translation: [tx, ty, tz]
* parent: base_link
* imu:
* extrinsics:
* quaternion: [qx, qy, qz, qw]
* translation: [tx, ty, tz]
* parent: camera
*
Following the common ROS conventions, the robot reference frame is assumed to be base_link
(default).
Of course, this mechanism of defining a tree of sensor poses in a YAML file only works for static (rigid) sensor assemblies, where the transformations between them is always static.
The data is returned as a std::map
from sensor labels to poses within the robot reference frame.
This function takes as input the YAML filename to load.
See also: