#include <Eigen3/Dense>#include <iostream>#include <geometry_msgs/Pose.h>#include <geometry_msgs/Point32.h>#include <geometry_msgs/Pose2D.h>#include <sensor_msgs/LaserScan.h>

Go to the source code of this file.
Classes | |
| struct | pose_graph::PoseConstraint |
| A single pose constraint (including precision matrix) between two nodes. More... | |
Namespaces | |
| namespace | pose_graph |
Typedefs | |
| typedef Eigen3::Matrix< double, 6, 6 > | pose_graph::PrecisionMatrix |
Functions | |
| geometry_msgs::Point | pose_graph::computeBarycenter (const sensor_msgs::LaserScan &scan) |
| geometry_msgs::Point | pose_graph::convertToPoint (const geometry_msgs::Point32 &p) |
| double | pose_graph::euclideanDistance (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
| double | pose_graph::euclideanDistance (const geometry_msgs::Pose2D &p1, const geometry_msgs::Pose2D &p2, const double rad_to_m=1.0) |
| geometry_msgs::Pose | pose_graph::getPose (const PoseConstraint &c) |
| Given a pose constraint, return the expected relative pose. | |
| double | pose_graph::length (const Eigen3::Vector3d &v) |
| Norm of a vector. | |
| double | pose_graph::length (const PoseConstraint &constraint) |
| Norm of mean translation part of a Pose constraint. | |
| double | pose_graph::length (const geometry_msgs::Point &p) |
| PoseConstraint | pose_graph::makeConstraint (const Eigen3::Affine3d &trans, const Eigen3::Matrix< double, 6, 6 > &prec) |
| PrecisionMatrix | pose_graph::makePrecisionMatrix (const double x_prec, const double y_prec, const double theta_prec) |
| Given precisions of x, y, and theta (yaw), construct a 6x6 diagonal precision matrix Precisions of unspecified components (z, roll, pitch) are set to 1. Theta precision is converted to precision of z component of quaternion using a crude approximation. | |
| PrecisionMatrix | pose_graph::makePrecisionMatrix (const double x_prec, const double y_prec, const double xy_prec, const double theta_prec) |
| Given precisions of x, y, and theta (yaw), as well as xy precision, construct a 6x6 diagonal precision matrix Precisions of unspecified components (z, roll, pitch) are set to 1. Theta precision is converted to precision of z component of quaternion using a crude approximation. | |
| ostream & | pose_graph::operator<< (ostream &str, const PoseConstraint &constraint) |
Contains definitions of geometric objects stored in the pose graph
Definition in file geometry.h.