Skip to content

Commit 6088963

Browse files
authored
Refactor/ros to pose vec (#26)
* converted template to overloads * removed unused tf2 imports
1 parent c89beaf commit 6088963

File tree

2 files changed

+55
-93
lines changed

2 files changed

+55
-93
lines changed

cpp_test/test_ros_conversions.cpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -109,22 +109,6 @@ TEST(to_pose_msgs, vector_of_euler) {
109109
ASSERT_EQ(out.size(), 3);
110110
}
111111

112-
template <typename T>
113-
concept AcceptsRosToPoseVec = requires(const T& t) {
114-
vortex::utils::ros_conversions::ros_to_pose_vec(t);
115-
};
116-
117-
static_assert(AcceptsRosToPoseVec<geometry_msgs::msg::Pose>);
118-
static_assert(AcceptsRosToPoseVec<geometry_msgs::msg::PoseStamped>);
119-
static_assert(
120-
AcceptsRosToPoseVec<geometry_msgs::msg::PoseWithCovarianceStamped>);
121-
static_assert(AcceptsRosToPoseVec<geometry_msgs::msg::PoseArray>);
122-
123-
static_assert(!AcceptsRosToPoseVec<int>);
124-
static_assert(!AcceptsRosToPoseVec<double>);
125-
static_assert(!AcceptsRosToPoseVec<Eigen::Vector3d>);
126-
static_assert(!AcceptsRosToPoseVec<HasQuatPose>);
127-
128112
TEST(ros_to_pose_vec, pose) {
129113
geometry_msgs::msg::Pose p;
130114
p.position.x = 1;

include/vortex/utils/ros_conversions.hpp

Lines changed: 55 additions & 77 deletions
Original file line numberDiff line numberDiff line change
@@ -20,42 +20,6 @@
2020

2121
namespace vortex::utils::ros_conversions {
2222

23-
/**
24-
* @brief Helper concept to check if two types are the same
25-
* after removing cv-ref qualifiers.
26-
*
27-
* @tparam T First type.
28-
* @tparam U Second type.
29-
*/
30-
template <typename T, typename U>
31-
concept same_bare_as = std::same_as<std::remove_cvref_t<T>, U>;
32-
33-
/**
34-
* @brief Concept describing ROS pose message types supported by
35-
* ros_to_eigen6d().
36-
*
37-
* Supported types are:
38-
*
39-
* - `geometry_msgs::msg::Pose`
40-
*
41-
* - `geometry_msgs::msg::PoseStamped`
42-
*
43-
* - `geometry_msgs::msg::PoseWithCovariance`
44-
*
45-
* - `geometry_msgs::msg::PoseWithCovarianceStamped`
46-
*
47-
* - `geometry_msgs::msg::PoseArray`
48-
*
49-
* @tparam T The candidate type to test.
50-
*/
51-
template <typename T>
52-
concept ROSPoseLike =
53-
same_bare_as<T, geometry_msgs::msg::Pose> ||
54-
same_bare_as<T, geometry_msgs::msg::PoseStamped> ||
55-
same_bare_as<T, geometry_msgs::msg::PoseWithCovariance> ||
56-
same_bare_as<T, geometry_msgs::msg::PoseWithCovarianceStamped> ||
57-
same_bare_as<T, geometry_msgs::msg::PoseArray>;
58-
5923
/**
6024
* @brief Converts a PoseLike object to a ROS geometry_msgs::msg::Pose.
6125
*
@@ -136,49 +100,63 @@ inline vortex::utils::types::Pose ros_pose_to_pose(
136100
}
137101

138102
/**
139-
* @brief Extracts one or more internal Pose objects from a ROS pose message.
140-
*
141-
* Supported input types are:
142-
*
143-
* - `geometry_msgs::msg::Pose`
144-
*
145-
* - `geometry_msgs::msg::PoseStamped`
146-
*
147-
* - `geometry_msgs::msg::PoseWithCovariance`
148-
*
149-
* - `geometry_msgs::msg::PoseWithCovarianceStamped`
150-
*
151-
* - `geometry_msgs::msg::PoseArray`
152-
*
153-
* Messages containing a single pose produce a vector with one element.
154-
* PoseArray messages produce a vector with one element per pose.
155-
*
156-
* @tparam T ROS message type satisfying ROSPoseLike
157-
* @param msg ROS pose message
158-
* @return std::vector<vortex::utils::types::Pose> Extracted internal poses
103+
* @brief Converts a ROS geometry_msgs::msg::Pose to an internal Pose vector
104+
* type.
105+
* @param pose geometry_msgs::msg::Pose
106+
* @return std::vector<vortex::utils::types::Pose> Internal pose representation
107+
*/
108+
inline std::vector<vortex::utils::types::Pose> ros_to_pose_vec(
109+
const geometry_msgs::msg::Pose& msg) {
110+
return {ros_pose_to_pose(msg)};
111+
}
112+
113+
/**
114+
* @brief Converts a ROS geometry_msgs::msg::PoseStamped to an internal Pose
115+
* vector type.
116+
* @param pose geometry_msgs::msg::PoseStamped
117+
* @return std::vector<vortex::utils::types::Pose> Internal pose representation
118+
*/
119+
inline std::vector<vortex::utils::types::Pose> ros_to_pose_vec(
120+
const geometry_msgs::msg::PoseStamped& msg) {
121+
return {ros_pose_to_pose(msg.pose)};
122+
}
123+
124+
/**
125+
* @brief Converts a ROS geometry_msgs::msg::PoseWithCovariance to an internal
126+
* Pose vector type.
127+
* @param pose geometry_msgs::msg::PoseWithCovariance
128+
* @return std::vector<vortex::utils::types::Pose> Internal pose representation
129+
*/
130+
inline std::vector<vortex::utils::types::Pose> ros_to_pose_vec(
131+
const geometry_msgs::msg::PoseWithCovariance& msg) {
132+
return {ros_pose_to_pose(msg.pose)};
133+
}
134+
135+
/**
136+
* @brief Converts a ROS geometry_msgs::msg::PoseWithCovarianceStamped to an
137+
* internal Pose vector type.
138+
* @param pose geometry_msgs::msg::PoseWithCovarianceStamped
139+
* @return std::vector<vortex::utils::types::Pose> Internal pose representation
140+
*/
141+
inline std::vector<vortex::utils::types::Pose> ros_to_pose_vec(
142+
const geometry_msgs::msg::PoseWithCovarianceStamped& msg) {
143+
return {ros_pose_to_pose(msg.pose.pose)};
144+
}
145+
146+
/**
147+
* @brief Converts a ROS geometry_msgs::msg::PoseArray to an internal Pose
148+
* vector type.
149+
* @param pose geometry_msgs::msg::PoseArray
150+
* @return std::vector<vortex::utils::types::Pose> Internal pose representation
159151
*/
160-
template <ROSPoseLike T>
161-
std::vector<vortex::utils::types::Pose> ros_to_pose_vec(const T& msg) {
162-
if constexpr (same_bare_as<T, geometry_msgs::msg::Pose>) {
163-
return {ros_pose_to_pose(msg)};
164-
} else if constexpr (same_bare_as<T, geometry_msgs::msg::PoseStamped>) {
165-
return {ros_pose_to_pose(msg.pose)};
166-
} else if constexpr (same_bare_as<T,
167-
geometry_msgs::msg::PoseWithCovariance>) {
168-
return {ros_pose_to_pose(msg.pose)};
169-
} else if constexpr (same_bare_as<
170-
T,
171-
geometry_msgs::msg::PoseWithCovarianceStamped>) {
172-
return {ros_pose_to_pose(msg.pose.pose)};
173-
} else if constexpr (same_bare_as<T, geometry_msgs::msg::PoseArray>) {
174-
std::vector<vortex::utils::types::Pose> poses;
175-
poses.reserve(msg.poses.size());
176-
177-
for (const auto& pose : msg.poses) {
178-
poses.push_back(ros_pose_to_pose(pose));
179-
}
180-
return poses;
152+
inline std::vector<vortex::utils::types::Pose> ros_to_pose_vec(
153+
const geometry_msgs::msg::PoseArray& msg) {
154+
std::vector<vortex::utils::types::Pose> poses;
155+
poses.reserve(msg.poses.size());
156+
for (const auto& pose : msg.poses) {
157+
poses.push_back(ros_pose_to_pose(pose));
181158
}
159+
return poses;
182160
}
183161

184162
} // namespace vortex::utils::ros_conversions

0 commit comments

Comments
 (0)