pose_cov_ops.h
Go to the documentation of this file.
1 /* pose_cov_ops
2  *
3  * Copyright 2012-2022, Jose Luis Blanco Claraco
4  * License: BSD 3-Clause License
5  */
6 
7 #pragma once
8 
9 #if PACKAGE_ROS_VERSION == 1
10 #include <geometry_msgs/Pose.h>
11 #include <geometry_msgs/PoseWithCovariance.h>
12 #else
13 #include <geometry_msgs/msg/pose.hpp>
14 #include <geometry_msgs/msg/pose_with_covariance.hpp>
15 #endif
17 
18 namespace pose_cov_ops {
19 
20 #if PACKAGE_ROS_VERSION == 1
23 #else
26 #endif
27 
30 void compose(const Pose &a, const Pose &b, Pose &out);
31 void compose(const PoseWithCovariance &a, const PoseWithCovariance &b,
32  PoseWithCovariance &out);
33 void compose(const PoseWithCovariance &a, const Pose &b,
34  PoseWithCovariance &out);
35 void compose(const Pose &a, const PoseWithCovariance &b,
36  PoseWithCovariance &out);
37 
38 // Return-by-value versions:
39 static inline Pose compose(const Pose &a, const Pose &b) {
40  Pose out;
41  compose(a, b, out);
42  return out;
43 }
45  const PoseWithCovariance &b) {
47  compose(a, b, out);
48  return out;
49 }
51  const Pose &b) {
53  compose(a, b, out);
54  return out;
55 }
56 static inline PoseWithCovariance compose(const Pose &a,
57  const PoseWithCovariance &b) {
59  compose(a, b, out);
60  return out;
61 }
62 
63 // Return-by-value versions using TF2 transforms:
65  const tf2::Transform &b);
66 
71 void inverseCompose(const Pose &a, const Pose &b, Pose &out);
73  PoseWithCovariance &out);
74 void inverseCompose(const PoseWithCovariance &a, const Pose &b,
75  PoseWithCovariance &out);
76 void inverseCompose(const Pose &a, const PoseWithCovariance &b,
77  PoseWithCovariance &out);
78 // Return-by-value versions:
79 static inline Pose inverseCompose(const Pose &a, const Pose &b) {
80  Pose out;
81  inverseCompose(a, b, out);
82  return out;
83 }
85  const PoseWithCovariance &b) {
87  inverseCompose(a, b, out);
88  return out;
89 }
91  const Pose &b) {
93  inverseCompose(a, b, out);
94  return out;
95 }
96 static inline PoseWithCovariance inverseCompose(const Pose &a,
97  const PoseWithCovariance &b) {
99  inverseCompose(a, b, out);
100  return out;
101 }
102 
103 // Return-by-value versions using TF2 transforms:
105  const tf2::Transform &b);
106 
109 } // namespace pose_cov_ops
pose_cov_ops::compose
void compose(const Pose &a, const Pose &b, Pose &out)
Definition: pose_cov_ops.cpp:20
pose_cov_ops::PoseWithCovariance
geometry_msgs::msg::PoseWithCovariance PoseWithCovariance
Definition: pose_cov_ops.h:25
tf2::Transform
pose_cov_ops::inverseCompose
void inverseCompose(const Pose &a, const Pose &b, Pose &out)
Definition: pose_cov_ops.cpp:71
pose_cov_ops
Definition: pose_cov_ops.h:18
Transform.h
pose_cov_ops::Pose
geometry_msgs::msg::Pose Pose
Definition: pose_cov_ops.h:24


pose_cov_ops
Author(s):
autogenerated on Wed Jan 22 2025 03:47:34