Function mrpt::poses::sensor_poses_from_yaml_file
Defined in File sensor_poses.h
Function Documentation
-
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
extrinsicsmap containing the SE(3) relative pose between theparentframe 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::mapfrom sensor labels to poses within the robot reference frame.This function takes as input the YAML filename to load.
See also
CPose3D, mrpt::obs::CObservation, sensor_poses_from_yaml()