#include <Eigen3/Dense>#include <tf/transform_datatypes.h>#include <geometry_msgs/Pose.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Pose2D.h>#include <nav_msgs/OccupancyGrid.h>

Go to the source code of this file.
Namespaces | |
| namespace | pose_graph |
Functions | |
| Pose | pose_graph::applyTransform (const Affine3d &trans, const Pose &pose) |
| Apply an Eigen transformation to a ROS pose. | |
| Pose | pose_graph::convertToPose (const Pose2D &pose2d) |
| Convert to Pose. | |
| Pose | pose_graph::convertToPose (const Affine3d trans) |
| Convert transform to pose. | |
| nav_msgs::MapMetaData | pose_graph::getMapInfo (const Pose &pose, const double size, const double resolution) |
| Return dimensions of a map centered at pose of the given size (meters) and resolution. | |
| Pose2D | pose_graph::makePose2D (double x, double y, double theta=0.0) |
| Construct a pose2d. | |
| Pose | pose_graph::perturbPose (const Pose &pose, double r) |
| Perturb x, y components of pose by uniform noise between -r and r. | |
| Point | pose_graph::pointInReferenceFrame (const Point &p, const Pose &pose) |
| Given point coordinates w.r.t a pose, return its coordinates in reference frame. | |
| Affine3d | pose_graph::poseToWorldTransform (const Pose &pose) |
| Return transformation from pose frame to world frame. | |
| Pose2D | pose_graph::projectToPose2D (const Pose &pose) |
| Project Pose to Pose2D. | |
| Eigen3::Vector4d | pose_graph::quaternionMsgToVector4d (const geometry_msgs::Quaternion &m) |
| Convert ROS quaternion to Eigen Vector4d in x,y,z,w order. | |
| Pose | pose_graph::relativePose (const Pose &pose1, const Pose &pose2) |
| Affine3d | pose_graph::relativeTransform (const Pose &pose1, const Pose &pose2) |
| Return transformation from frame of pose1 to frame of pose2. | |
| Affine3d | pose_graph::relativeTransform (const Pose2D &pose1, const Pose2D &pose2) |
| Return transformation from frame of pose1 to frame of pose2. | |
| Affine3d | pose_graph::transformBetween (const Pose &pose1, const Pose &pose2) |
| nav_msgs::OccupancyGrid | pose_graph::transformGrid (const Affine3d &trans, const nav_msgs::OccupancyGrid &g) |
| Transform an occupancy grid (just transforms the origin) | |
| Point32 | pose_graph::transformPoint (const Affine3d &trans, const Point32 &pt) |
| Apply an Eigen transformation to a ROS point. | |
| Point | pose_graph::transformPoint (const Affine3d &trans, const Point &pt) |
| Apply an Eigen transformation to a ROS point. | |
| Eigen3::Vector4d | pose_graph::translationToVector4d (const geometry_msgs::Point &p) |
| Convert a ROS point to an Eigen 4d vector with 1 at the end. | |
Contains internally used convenience operations involving conversion between ROS, Eigen, and TF, as well as operations on transforms and poses
Definition in file transforms.h.