Skip to content

Commit 911555a

Browse files
authored
Nacho/cleanup get transform util (#4181)
* remove unused header Signed-off-by: Ignacio Vizzo <[email protected]> * First step. Return an optional value instead of user provided output. Signed-off-by: Ignacio Vizzo <[email protected]> * Second step, update the consumers of this utility function Signed-off-by: Ignacio Vizzo <[email protected]> * Third step: swap source/target to make it consistent with tf lookups Otherwise is very confusing for any user who is user to the tf2::Buffer::lookupTransform method Signed-off-by: Ignacio Vizzo <[email protected]> * transform tolerance -> transform timeout I find this "transform tolerance" to specify something else. Once again, I believe that sticking to tf2 name conventions is better and improve readability for users already used to the tf2 API Signed-off-by: Ignacio Vizzo <[email protected]> * Last step, convert functions to template functions This allow us to also query for the TransformStamped message from the lookupTransform method. Signed-off-by: Ignacio Vizzo <[email protected]> * Add nodiscard to avoid confusiong API calls Signed-off-by: Ignacio Vizzo <[email protected]> * Update docs Signed-off-by: Ignacio Vizzo <[email protected]> * Revert "transform tolerance -> transform timeout" This reverts commit ca7d06b. Signed-off-by: Ignacio Vizzo <[email protected]> * Fix linter 🤦 Signed-off-by: Ignacio Vizzo <[email protected]> * reset to main Signed-off-by: Ignacio Vizzo <[email protected]> * Add 2 new utils functions to query transforms using messages Signed-off-by: Ignacio Vizzo <[email protected]> * Move utility function to base class to reuse implementation Signed-off-by: Ignacio Vizzo <[email protected]> * Fix Typo Signed-off-by: Ignacio Vizzo <[email protected]> --------- Signed-off-by: Ignacio Vizzo <[email protected]>
1 parent b0e6d3d commit 911555a

File tree

7 files changed

+134
-83
lines changed

7 files changed

+134
-83
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/source.hpp

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,9 @@
2424
#include "tf2/time.h"
2525
#include "tf2_ros/buffer.h"
2626

27-
#include "nav2_util/lifecycle_node.hpp"
28-
2927
#include "nav2_collision_monitor/types.hpp"
28+
#include "nav2_util/lifecycle_node.hpp"
29+
#include "std_msgs/msg/header.hpp"
3030

3131
namespace nav2_collision_monitor
3232
{
@@ -123,6 +123,21 @@ class Source
123123
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
124124
std::vector<rclcpp::Parameter> parameters);
125125

126+
/**
127+
* @brief Obtain the transform to get data from source frame and time where it was received to the
128+
* base frame and current time (if base_shift_correction_ is true) or the transform without time
129+
* shift considered which is less accurate but much more faster option not dependent on state
130+
* estimation frames.
131+
* @param curr_time Current node time
132+
* @param data_header Current header which contains the frame_id and the stamp
133+
* @param tf_transform Output source->base_frame_id_ transform
134+
* @return True if got correct transform, otherwise false
135+
*/
136+
bool getTransform(
137+
const rclcpp::Time & curr_time,
138+
const std_msgs::msg::Header & data_header,
139+
tf2::Transform & tf_transform) const;
140+
126141
// ----- Variables -----
127142

128143
/// @brief Collision Monitor node

nav2_collision_monitor/src/pointcloud.cpp

Lines changed: 2 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -79,28 +79,8 @@ bool PointCloud::getData(
7979
}
8080

8181
tf2::Transform tf_transform;
82-
if (base_shift_correction_) {
83-
// Obtaining the transform to get data from source frame and time where it was received
84-
// to the base frame and current time
85-
if (
86-
!nav2_util::getTransform(
87-
data_->header.frame_id, data_->header.stamp,
88-
base_frame_id_, curr_time, global_frame_id_,
89-
transform_tolerance_, tf_buffer_, tf_transform))
90-
{
91-
return false;
92-
}
93-
} else {
94-
// Obtaining the transform to get data from source frame to base frame without time shift
95-
// considered. Less accurate but much more faster option not dependent on state estimation
96-
// frames.
97-
if (
98-
!nav2_util::getTransform(
99-
data_->header.frame_id, base_frame_id_,
100-
transform_tolerance_, tf_buffer_, tf_transform))
101-
{
102-
return false;
103-
}
82+
if (!getTransform(curr_time, data_->header, tf_transform)) {
83+
return false;
10484
}
10585

10686
sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");

nav2_collision_monitor/src/range.cpp

Lines changed: 2 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -88,28 +88,8 @@ bool Range::getData(
8888
}
8989

9090
tf2::Transform tf_transform;
91-
if (base_shift_correction_) {
92-
// Obtaining the transform to get data from source frame and time where it was received
93-
// to the base frame and current time
94-
if (
95-
!nav2_util::getTransform(
96-
data_->header.frame_id, data_->header.stamp,
97-
base_frame_id_, curr_time, global_frame_id_,
98-
transform_tolerance_, tf_buffer_, tf_transform))
99-
{
100-
return false;
101-
}
102-
} else {
103-
// Obtaining the transform to get data from source frame to base frame without time shift
104-
// considered. Less accurate but much more faster option not dependent on state estimation
105-
// frames.
106-
if (
107-
!nav2_util::getTransform(
108-
data_->header.frame_id, base_frame_id_,
109-
transform_tolerance_, tf_buffer_, tf_transform))
110-
{
111-
return false;
112-
}
91+
if (!getTransform(curr_time, data_->header, tf_transform)) {
92+
return false;
11393
}
11494

11595
// Calculate poses and refill data array

nav2_collision_monitor/src/scan.cpp

Lines changed: 2 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -78,28 +78,8 @@ bool Scan::getData(
7878
}
7979

8080
tf2::Transform tf_transform;
81-
if (base_shift_correction_) {
82-
// Obtaining the transform to get data from source frame and time where it was received
83-
// to the base frame and current time
84-
if (
85-
!nav2_util::getTransform(
86-
data_->header.frame_id, data_->header.stamp,
87-
base_frame_id_, curr_time, global_frame_id_,
88-
transform_tolerance_, tf_buffer_, tf_transform))
89-
{
90-
return false;
91-
}
92-
} else {
93-
// Obtaining the transform to get data from source frame to base frame without time shift
94-
// considered. Less accurate but much more faster option not dependent on state estimation
95-
// frames.
96-
if (
97-
!nav2_util::getTransform(
98-
data_->header.frame_id, base_frame_id_,
99-
transform_tolerance_, tf_buffer_, tf_transform))
100-
{
101-
return false;
102-
}
81+
if (!getTransform(curr_time, data_->header, tf_transform)) {
82+
return false;
10383
}
10484

10585
// Calculate poses and refill data array

nav2_collision_monitor/src/source.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include "geometry_msgs/msg/transform_stamped.hpp"
2020

2121
#include "nav2_util/node_utils.hpp"
22+
#include "nav2_util/robot_utils.hpp"
2223

2324
namespace nav2_collision_monitor
2425
{
@@ -131,4 +132,30 @@ Source::dynamicParametersCallback(
131132
return result;
132133
}
133134

135+
bool Source::getTransform(
136+
const rclcpp::Time & curr_time,
137+
const std_msgs::msg::Header & data_header,
138+
tf2::Transform & tf_transform) const
139+
{
140+
if (base_shift_correction_) {
141+
if (
142+
!nav2_util::getTransform(
143+
data_header.frame_id, data_header.stamp,
144+
base_frame_id_, curr_time, global_frame_id_,
145+
transform_tolerance_, tf_buffer_, tf_transform))
146+
{
147+
return false;
148+
}
149+
} else {
150+
if (
151+
!nav2_util::getTransform(
152+
data_header.frame_id, base_frame_id_,
153+
transform_tolerance_, tf_buffer_, tf_transform))
154+
{
155+
return false;
156+
}
157+
}
158+
return true;
159+
}
160+
134161
} // namespace nav2_collision_monitor

nav2_util/include/nav2_util/robot_utils.hpp

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "geometry_msgs/msg/pose_stamped.hpp"
2424
#include "geometry_msgs/msg/twist.hpp"
2525
#include "geometry_msgs/msg/twist_stamped.hpp"
26+
#include "geometry_msgs/msg/transform_stamped.hpp"
2627
#include "tf2/time.h"
2728
#include "tf2_ros/buffer.h"
2829
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
@@ -99,6 +100,45 @@ bool getTransform(
99100
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
100101
tf2::Transform & tf2_transform);
101102

103+
/**
104+
* @brief Obtains a transform from source_frame_id -> to target_frame_id
105+
* @param source_frame_id Source frame ID to convert from
106+
* @param target_frame_id Target frame ID to convert to
107+
* @param transform_tolerance Transform tolerance
108+
* @param tf_buffer TF buffer to use for the transformation
109+
* @param transform_msg Output source->target transform msg
110+
* @return True if got correct transform, otherwise false
111+
*/
112+
bool getTransform(
113+
const std::string & source_frame_id,
114+
const std::string & target_frame_id,
115+
const tf2::Duration & transform_tolerance,
116+
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
117+
geometry_msgs::msg::TransformStamped & transform_msg);
118+
119+
/**
120+
* @brief Obtains a transform from source_frame_id at source_time ->
121+
* to target_frame_id at target_time time
122+
* @param source_frame_id Source frame ID to convert from
123+
* @param source_time Source timestamp to convert from
124+
* @param target_frame_id Target frame ID to convert to
125+
* @param target_time Current node time to interpolate to
126+
* @param fixed_frame_id The frame in which to assume the transform is constant in time
127+
* @param transform_tolerance Transform tolerance
128+
* @param tf_buffer TF buffer to use for the transformation
129+
* @param transform_msg Output source->target transform msg
130+
* @return True if got correct transform, otherwise false
131+
*/
132+
bool getTransform(
133+
const std::string & source_frame_id,
134+
const rclcpp::Time & source_time,
135+
const std::string & target_frame_id,
136+
const rclcpp::Time & target_time,
137+
const std::string & fixed_frame_id,
138+
const tf2::Duration & transform_tolerance,
139+
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
140+
geometry_msgs::msg::TransformStamped & transform_msg);
141+
102142
/**
103143
* @brief Validates a twist message contains no nans or infs
104144
* @param msg Twist message to validate

nav2_util/src/robot_utils.cpp

Lines changed: 44 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -82,19 +82,16 @@ bool getTransform(
8282
const std::string & target_frame_id,
8383
const tf2::Duration & transform_tolerance,
8484
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
85-
tf2::Transform & tf2_transform)
85+
geometry_msgs::msg::TransformStamped & transform_msg)
8686
{
87-
geometry_msgs::msg::TransformStamped transform;
88-
tf2_transform.setIdentity(); // initialize by identical transform
89-
9087
if (source_frame_id == target_frame_id) {
9188
// We are already in required frame
9289
return true;
9390
}
9491

9592
try {
9693
// Obtaining the transform to get data from source to target frame
97-
transform = tf_buffer->lookupTransform(
94+
transform_msg = tf_buffer->lookupTransform(
9895
target_frame_id, source_frame_id,
9996
tf2::TimePointZero, transform_tolerance);
10097
} catch (tf2::TransformException & e) {
@@ -104,29 +101,40 @@ bool getTransform(
104101
source_frame_id.c_str(), target_frame_id.c_str(), e.what());
105102
return false;
106103
}
107-
108-
// Convert TransformStamped to TF2 transform
109-
tf2::fromMsg(transform.transform, tf2_transform);
110104
return true;
111105
}
112106

113107
bool getTransform(
114108
const std::string & source_frame_id,
115-
const rclcpp::Time & source_time,
116109
const std::string & target_frame_id,
117-
const rclcpp::Time & target_time,
118-
const std::string & fixed_frame_id,
119110
const tf2::Duration & transform_tolerance,
120111
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
121112
tf2::Transform & tf2_transform)
122113
{
123-
geometry_msgs::msg::TransformStamped transform;
124114
tf2_transform.setIdentity(); // initialize by identical transform
115+
geometry_msgs::msg::TransformStamped transform;
116+
if (getTransform(source_frame_id, target_frame_id, transform_tolerance, tf_buffer, transform)) {
117+
// Convert TransformStamped to TF2 transform
118+
tf2::fromMsg(transform.transform, tf2_transform);
119+
return true;
120+
}
121+
return false;
122+
}
125123

124+
bool getTransform(
125+
const std::string & source_frame_id,
126+
const rclcpp::Time & source_time,
127+
const std::string & target_frame_id,
128+
const rclcpp::Time & target_time,
129+
const std::string & fixed_frame_id,
130+
const tf2::Duration & transform_tolerance,
131+
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
132+
geometry_msgs::msg::TransformStamped & transform_msg)
133+
{
126134
try {
127135
// Obtaining the transform to get data from source to target frame.
128136
// This also considers the time shift between source and target.
129-
transform = tf_buffer->lookupTransform(
137+
transform_msg = tf_buffer->lookupTransform(
130138
target_frame_id, target_time,
131139
source_frame_id, source_time,
132140
fixed_frame_id, transform_tolerance);
@@ -138,11 +146,32 @@ bool getTransform(
138146
return false;
139147
}
140148

141-
// Convert TransformStamped to TF2 transform
142-
tf2::fromMsg(transform.transform, tf2_transform);
143149
return true;
144150
}
145151

152+
bool getTransform(
153+
const std::string & source_frame_id,
154+
const rclcpp::Time & source_time,
155+
const std::string & target_frame_id,
156+
const rclcpp::Time & target_time,
157+
const std::string & fixed_frame_id,
158+
const tf2::Duration & transform_tolerance,
159+
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
160+
tf2::Transform & tf2_transform)
161+
{
162+
geometry_msgs::msg::TransformStamped transform;
163+
tf2_transform.setIdentity(); // initialize by identical transform
164+
if (getTransform(
165+
source_frame_id, source_time, target_frame_id, target_time, fixed_frame_id,
166+
transform_tolerance, tf_buffer, transform))
167+
{
168+
// Convert TransformStamped to TF2 transform
169+
tf2::fromMsg(transform.transform, tf2_transform);
170+
return true;
171+
}
172+
return false;
173+
}
174+
146175
bool validateTwist(const geometry_msgs::msg::Twist & msg)
147176
{
148177
if (std::isinf(msg.linear.x) || std::isnan(msg.linear.x)) {

0 commit comments

Comments
 (0)