#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_with_covariance.hpp>
#include <tf2/LinearMath/Transform.h>
Go to the source code of this file.
Namespaces | |
pose_cov_ops | |
Typedefs | |
using | pose_cov_ops::Pose = geometry_msgs::msg::Pose |
using | pose_cov_ops::PoseWithCovariance = geometry_msgs::msg::PoseWithCovariance |
Functions | |
Pose composition: out = a (+) b | |
void | pose_cov_ops::compose (const Pose &a, const Pose &b, Pose &out) |
void | pose_cov_ops::compose (const PoseWithCovariance &a, const PoseWithCovariance &b, PoseWithCovariance &out) |
void | pose_cov_ops::compose (const PoseWithCovariance &a, const Pose &b, PoseWithCovariance &out) |
void | pose_cov_ops::compose (const Pose &a, const PoseWithCovariance &b, PoseWithCovariance &out) |
static Pose | pose_cov_ops::compose (const Pose &a, const Pose &b) |
static PoseWithCovariance | pose_cov_ops::compose (const PoseWithCovariance &a, const PoseWithCovariance &b) |
static PoseWithCovariance | pose_cov_ops::compose (const PoseWithCovariance &a, const Pose &b) |
static PoseWithCovariance | pose_cov_ops::compose (const Pose &a, const PoseWithCovariance &b) |
PoseWithCovariance | pose_cov_ops::compose (const PoseWithCovariance &a, const tf2::Transform &b) |
Pose inverse composition (a "as seen from" b): out = a (-) b | |
void | pose_cov_ops::inverseCompose (const Pose &a, const Pose &b, Pose &out) |
void | pose_cov_ops::inverseCompose (const PoseWithCovariance &a, const PoseWithCovariance &b, PoseWithCovariance &out) |
void | pose_cov_ops::inverseCompose (const PoseWithCovariance &a, const Pose &b, PoseWithCovariance &out) |
void | pose_cov_ops::inverseCompose (const Pose &a, const PoseWithCovariance &b, PoseWithCovariance &out) |
static Pose | pose_cov_ops::inverseCompose (const Pose &a, const Pose &b) |
static PoseWithCovariance | pose_cov_ops::inverseCompose (const PoseWithCovariance &a, const PoseWithCovariance &b) |
static PoseWithCovariance | pose_cov_ops::inverseCompose (const PoseWithCovariance &a, const Pose &b) |
static PoseWithCovariance | pose_cov_ops::inverseCompose (const Pose &a, const PoseWithCovariance &b) |
PoseWithCovariance | pose_cov_ops::inverseCompose (const PoseWithCovariance &a, const tf2::Transform &b) |