Skip to content

Commit 62322b8

Browse files
ahcordetfoote
andauthored
Enable Twist interpolator (#646)
Signed-off-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Tully Foote <[email protected]>
1 parent f63c7ae commit 62322b8

File tree

9 files changed

+960
-35
lines changed

9 files changed

+960
-35
lines changed

tf2/include/tf2/buffer_core.h

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646

4747
#include "LinearMath/Transform.h"
4848
#include "geometry_msgs/msg/transform_stamped.hpp"
49+
#include "geometry_msgs/msg/velocity_stamped.hpp"
4950
#include "rcutils/logging_macros.h"
5051
#include "tf2/buffer_core_interface.h"
5152
#include "tf2/exceptions.h"
@@ -157,6 +158,28 @@ class BufferCore : public BufferCoreInterface
157158
const std::string & source_frame, const TimePoint & source_time,
158159
const std::string & fixed_frame) const override;
159160

161+
TF2_PUBLIC
162+
geometry_msgs::msg::VelocityStamped lookupVelocity(
163+
const std::string & tracking_frame, const std::string & observation_frame,
164+
const TimePoint & time, const tf2::Duration & averaging_interval) const;
165+
166+
/** \brief Lookup the velocity of the moving_frame in the reference_frame
167+
* \param reference_frame The frame in which to track
168+
* \param moving_frame The frame to track
169+
* \param time The time at which to get the velocity
170+
* \param duration The period over which to average
171+
* \param velocity The velocity output
172+
*
173+
* Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException,
174+
* TransformReference::MaxDepthException
175+
*/
176+
TF2_PUBLIC
177+
geometry_msgs::msg::VelocityStamped lookupVelocity(
178+
const std::string & tracking_frame, const std::string & observation_frame,
179+
const std::string & reference_frame, const tf2::Vector3 & reference_point,
180+
const std::string & reference_point_frame,
181+
const TimePoint & time, const tf2::Duration & duration) const;
182+
160183
/** \brief Test if a transform is possible
161184
* \param target_frame The frame into which to transform
162185
* \param source_frame The frame from which to transform

tf2/src/buffer_core.cpp

Lines changed: 119 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@
3838
#include <utility>
3939
#include <vector>
4040

41+
#include <iostream>
42+
4143
#include "tf2/buffer_core.h"
4244
#include "tf2/time_cache.h"
4345
#include "tf2/exceptions.h"
@@ -574,6 +576,123 @@ struct TransformAccum
574576
tf2::Vector3 result_vec;
575577
};
576578

579+
geometry_msgs::msg::VelocityStamped BufferCore::lookupVelocity(
580+
const std::string & tracking_frame, const std::string & observation_frame,
581+
const TimePoint & time, const tf2::Duration & averaging_interval) const
582+
{
583+
// ref point is origin of tracking_frame, ref_frame = obs_frame
584+
return lookupVelocity(
585+
tracking_frame, observation_frame, observation_frame, tf2::Vector3(
586+
0, 0,
587+
0), tracking_frame, time,
588+
averaging_interval);
589+
}
590+
591+
geometry_msgs::msg::VelocityStamped BufferCore::lookupVelocity(
592+
const std::string & tracking_frame, const std::string & observation_frame,
593+
const std::string & reference_frame, const tf2::Vector3 & reference_point,
594+
const std::string & reference_point_frame,
595+
const TimePoint & time, const tf2::Duration & averaging_interval) const
596+
{
597+
tf2::TimePoint latest_time;
598+
// TODO(anyone): This is incorrect, but better than nothing. Really we want the latest time for
599+
// any of the frames
600+
getLatestCommonTime(
601+
lookupFrameNumber(observation_frame),
602+
lookupFrameNumber(tracking_frame),
603+
latest_time,
604+
0);
605+
606+
auto time_seconds = tf2::timeToSec(time);
607+
auto averaging_interval_seconds = std::chrono::duration<double>(averaging_interval).count();
608+
609+
auto end_time =
610+
std::min(time_seconds + averaging_interval_seconds * 0.5, tf2::timeToSec(latest_time));
611+
612+
auto start_time =
613+
std::max(0.00001 + averaging_interval_seconds, end_time) - averaging_interval_seconds;
614+
// correct for the possiblity that start time was truncated above.
615+
auto corrected_averaging_interval = end_time - start_time;
616+
617+
tf2::Transform start, end;
618+
TimePoint time_out;
619+
lookupTransformImpl(
620+
observation_frame, tracking_frame, tf2::timeFromSec(
621+
start_time), start, time_out);
622+
lookupTransformImpl(observation_frame, tracking_frame, tf2::timeFromSec(end_time), end, time_out);
623+
624+
auto temp = start.getBasis().inverse() * end.getBasis();
625+
tf2::Quaternion quat_temp;
626+
temp.getRotation(quat_temp);
627+
auto o = start.getBasis() * quat_temp.getAxis();
628+
auto ang = quat_temp.getAngle();
629+
630+
double delta_x = end.getOrigin().getX() - start.getOrigin().getX();
631+
double delta_y = end.getOrigin().getY() - start.getOrigin().getY();
632+
double delta_z = end.getOrigin().getZ() - start.getOrigin().getZ();
633+
634+
tf2::Vector3 twist_vel((delta_x) / corrected_averaging_interval,
635+
(delta_y) / corrected_averaging_interval,
636+
(delta_z) / corrected_averaging_interval);
637+
tf2::Vector3 twist_rot = o * (ang / corrected_averaging_interval);
638+
639+
// correct for the position of the reference frame
640+
tf2::Transform inverse;
641+
lookupTransformImpl(
642+
reference_frame, tracking_frame, tf2::timeFromSec(
643+
time_seconds), inverse, time_out);
644+
tf2::Vector3 out_rot = inverse.getBasis() * twist_rot;
645+
tf2::Vector3 out_vel = inverse.getBasis() * twist_vel + inverse.getOrigin().cross(out_rot);
646+
647+
auto transform_point = [this](
648+
const std::string & target_frame,
649+
const std::string & source_frame,
650+
const tf2::Vector3 & point_in,
651+
double time_transform)
652+
{
653+
// transform point
654+
tf2::Transform transform;
655+
tf2::TimePoint time_out;
656+
lookupTransformImpl(
657+
target_frame, source_frame, tf2::timeFromSec(time_transform), transform, time_out);
658+
659+
tf2::Vector3 out;
660+
out = transform * point_in;
661+
return out;
662+
};
663+
664+
// Rereference the twist about a new reference point
665+
// Start by computing the original reference point in the reference frame:
666+
tf2::Vector3 p = tf2::Vector3(0, 0, 0);
667+
tf2::Vector3 rp_orig = transform_point(
668+
reference_frame, tracking_frame, p, time_seconds);
669+
670+
tf2::Vector3 rp_desired = transform_point(
671+
reference_frame, reference_point_frame, reference_point, time_seconds);
672+
673+
tf2::Vector3 delta = rp_desired - rp_orig;
674+
out_vel = out_vel + out_rot * delta;
675+
676+
std::chrono::nanoseconds ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
677+
tf2::timeFromSec(start_time + averaging_interval_seconds * 0.5).time_since_epoch());
678+
std::chrono::seconds s = std::chrono::duration_cast<std::chrono::seconds>(
679+
tf2::timeFromSec(start_time + averaging_interval_seconds * 0.5).time_since_epoch());
680+
geometry_msgs::msg::VelocityStamped velocity;
681+
velocity.header.stamp.sec = static_cast<int32_t>(s.count());
682+
velocity.header.stamp.nanosec = static_cast<uint32_t>(ns.count() % 1000000000ull);
683+
velocity.header.frame_id = reference_frame;
684+
velocity.body_frame_id = tracking_frame;
685+
686+
velocity.velocity.linear.x = out_vel.x();
687+
velocity.velocity.linear.y = out_vel.y();
688+
velocity.velocity.linear.z = out_vel.z();
689+
velocity.velocity.angular.x = out_rot.x();
690+
velocity.velocity.angular.y = out_rot.y();
691+
velocity.velocity.angular.z = out_rot.z();
692+
693+
return velocity;
694+
}
695+
577696
geometry_msgs::msg::TransformStamped
578697
BufferCore::lookupTransform(
579698
const std::string & target_frame, const std::string & source_frame,

tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.hpp

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848
#include "geometry_msgs/msg/pose_with_covariance.hpp"
4949
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
5050
#include "geometry_msgs/msg/polygon_stamped.hpp"
51+
#include "geometry_msgs/msg/velocity_stamped.hpp"
5152
#include "geometry_msgs/msg/wrench.hpp"
5253
#include "geometry_msgs/msg/wrench_stamped.hpp"
5354
#include "kdl/frames.hpp"
@@ -1313,6 +1314,68 @@ void fromMsg(const geometry_msgs::msg::Pose & in, tf2::Transform & out)
13131314
tf2::Quaternion(in.orientation.x, in.orientation.y, in.orientation.z, in.orientation.w));
13141315
}
13151316

1317+
/*********************/
1318+
/** VelocityStamped **/
1319+
/*********************/
1320+
1321+
/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs VelocityStamped type.
1322+
* This function is a specialization of the doTransform template defined in tf2/convert.h.
1323+
* \param t_in The point to transform, as a VelocityStamped message.
1324+
* \param t_out The transformed point, as a VelocityStamped message.
1325+
* \param transform The timestamped transform to apply, as a TransformStamped message.
1326+
*/
1327+
template<>
1328+
inline
1329+
void doTransform(
1330+
const geometry_msgs::msg::VelocityStamped & t_in,
1331+
geometry_msgs::msg::VelocityStamped & t_out,
1332+
const geometry_msgs::msg::TransformStamped & transform)
1333+
{
1334+
tf2::Vector3 twist_rot(t_in.velocity.angular.x,
1335+
t_in.velocity.angular.y,
1336+
t_in.velocity.angular.z);
1337+
tf2::Vector3 twist_vel(t_in.velocity.linear.x,
1338+
t_in.velocity.linear.y,
1339+
t_in.velocity.linear.z);
1340+
tf2::Transform transform_temp;
1341+
1342+
transform_temp.setOrigin(tf2::Vector3(
1343+
transform.transform.translation.x,
1344+
transform.transform.translation.y,
1345+
transform.transform.translation.z));
1346+
transform_temp.setRotation(tf2::Quaternion(
1347+
transform.transform.rotation.x,
1348+
transform.transform.rotation.y,
1349+
transform.transform.rotation.z,
1350+
transform.transform.rotation.w));
1351+
1352+
// tf2::Transform start, end;
1353+
// TimePoint time_out;
1354+
// lookupTransformImpl(
1355+
// observation_frame, tracking_frame, tf2::timeFromSec(
1356+
// start_time), start, time_out);
1357+
1358+
// tf::StampedTransform transform;
1359+
// lookupTransform(target_frame,msg_in.header.frame_id, msg_in.header.stamp, transform);
1360+
1361+
tf2::Vector3 out_rot = transform_temp.getBasis() * twist_rot;
1362+
tf2::Vector3 out_vel = transform_temp.getBasis() * twist_vel + \
1363+
transform_temp.getOrigin().cross(out_rot);
1364+
1365+
// geometry_msgs::TwistStamped interframe_twist;
1366+
// lookupVelocity(target_frame, msg_in.header.frame_id, msg_in.header.stamp,
1367+
// ros::Duration(0.1), interframe_twist);
1368+
// \todo get rid of hard coded number
1369+
1370+
t_out.header = t_in.header;
1371+
t_out.velocity.linear.x = out_vel.x() + t_in.velocity.linear.x;
1372+
t_out.velocity.linear.y = out_vel.y() + t_in.velocity.linear.y;
1373+
t_out.velocity.linear.z = out_vel.z() + t_in.velocity.linear.z;
1374+
t_out.velocity.angular.x = out_rot.x() + t_in.velocity.angular.x;
1375+
t_out.velocity.angular.y = out_rot.y() + t_in.velocity.angular.y;
1376+
t_out.velocity.angular.z = out_rot.z() + t_in.velocity.angular.z;
1377+
}
1378+
13161379
/**********************/
13171380
/*** WrenchStamped ****/
13181381
/**********************/

tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@
4646
#include "tf2_ros/buffer.h"
4747
#include "tf2_ros/transform_listener.h"
4848

49+
#include <geometry_msgs/msg/velocity_stamped.hpp>
50+
4951
std::unique_ptr<tf2_ros::Buffer> tf_buffer = nullptr;
5052
static const double EPS = 1e-3;
5153

@@ -625,6 +627,17 @@ TEST(TfGeometry, Wrench)
625627
EXPECT_NEAR(res.torque.z, 5, EPS);
626628
}
627629

630+
TEST(TfGeometry, Velocity)
631+
{
632+
geometry_msgs::msg::VelocityStamped v1, res;
633+
v1.header.frame_id = "world";
634+
v1.body_frame_id = "base_link";
635+
636+
geometry_msgs::msg::TransformStamped trafo;
637+
638+
tf2::doTransform(v1, res, trafo);
639+
}
640+
628641
int main(int argc, char ** argv)
629642
{
630643
testing::InitGoogleTest(&argc, argv);

tf2_py/src/tf2_py.cpp

Lines changed: 55 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -627,51 +627,71 @@ static PyObject * lookupTransformFullCore(PyObject * self, PyObject * args, PyOb
627627
// TODO(anyone): Create a converter that will actually return a python message
628628
return Py_BuildValue("O&", transform_converter, &transform);
629629
}
630-
/*
631-
static PyObject *lookupTwistCore(PyObject *self, PyObject *args, PyObject *kw)
630+
631+
static PyObject * lookupVelocityCore(PyObject * self, PyObject * args, PyObject * kw)
632632
{
633-
tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
634-
char *tracking_frame, *observation_frame;
635-
builtin_interfaces::msg::Time time;
633+
tf2::BufferCore * bc = ((buffer_core_t *)self)->bc;
634+
char * tracking_frame, * observation_frame;
635+
tf2::TimePoint time;
636636
tf2::Duration averaging_interval;
637-
static const char *keywords[] = { "tracking_frame", "observation_frame", "time", "averaging_interval", nullptr };
637+
static const char * keywords[] =
638+
{"tracking_frame", "observation_frame", "time", "averaging_interval", nullptr};
638639

639-
if (!PyArg_ParseTupleAndKeywords(args, kw, "ssO&O&", (char**)keywords, &tracking_frame, &observation_frame, rostime_converter, &time, rosduration_converter, &averaging_interval))
640+
if (!PyArg_ParseTupleAndKeywords(
641+
args, kw, "ssO&O&", (char **)keywords, &tracking_frame,
642+
&observation_frame, rostime_converter, &time, rosduration_converter, &averaging_interval))
643+
{
640644
return nullptr;
641-
geometry_msgs::msg::Twist twist;
642-
WRAP(twist = bc->lookupTwist(tracking_frame, observation_frame, time, averaging_interval));
643-
644-
return Py_BuildValue("(ddd)(ddd)",
645-
twist.linear.x, twist.linear.y, twist.linear.z,
646-
twist.angular.x, twist.angular.y, twist.angular.z);
645+
}
646+
geometry_msgs::msg::VelocityStamped velocity_stamped;
647+
WRAP(
648+
velocity_stamped =
649+
bc->lookupVelocity(tracking_frame, observation_frame, time, averaging_interval));
650+
651+
return Py_BuildValue(
652+
"(ddd)(ddd)",
653+
velocity_stamped.velocity.linear.x, velocity_stamped.velocity.linear.y,
654+
velocity_stamped.velocity.linear.z,
655+
velocity_stamped.velocity.angular.x, velocity_stamped.velocity.angular.y,
656+
velocity_stamped.velocity.angular.z);
647657
}
648658

649-
static PyObject *lookupTwistFullCore(PyObject *self, PyObject *args)
659+
static PyObject * lookupVelocityFullCore(PyObject * self, PyObject * args)
650660
{
651-
tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
652-
char *tracking_frame, *observation_frame, *reference_frame, *reference_point_frame;
653-
builtin_interfaces::msg::Time time;
661+
tf2::BufferCore * bc = ((buffer_core_t *)self)->bc;
662+
char * tracking_frame, * observation_frame, * reference_frame, * reference_point_frame;
663+
tf2::TimePoint time;
654664
tf2::Duration averaging_interval;
655665
double px, py, pz;
656666

657-
if (!PyArg_ParseTuple(args, "sss(ddd)sO&O&",
658-
&tracking_frame,
659-
&observation_frame,
660-
&reference_frame,
661-
&px, &py, &pz,
662-
&reference_point_frame,
663-
rostime_converter, &time,
664-
rosduration_converter, &averaging_interval))
667+
if (!PyArg_ParseTuple(
668+
args, "sss(ddd)sO&O&",
669+
&tracking_frame,
670+
&observation_frame,
671+
&reference_frame,
672+
&px, &py, &pz,
673+
&reference_point_frame,
674+
rostime_converter, &time,
675+
rosduration_converter, &averaging_interval))
676+
{
665677
return nullptr;
666-
geometry_msgs::msg::Twist twist;
667-
tf::Point pt(px, py, pz);
668-
WRAP(twist = bc->lookupTwist(tracking_frame, observation_frame, reference_frame, pt, reference_point_frame, time, averaging_interval));
669-
670-
return Py_BuildValue("(ddd)(ddd)",
671-
twist.linear.x, twist.linear.y, twist.linear.z,
672-
twist.angular.x, twist.angular.y, twist.angular.z);
678+
}
679+
geometry_msgs::msg::VelocityStamped velocity_stamped;
680+
tf2::Vector3 pt(px, py, pz);
681+
WRAP(
682+
velocity_stamped =
683+
bc->lookupVelocity(
684+
tracking_frame, observation_frame, reference_frame, pt,
685+
reference_point_frame, time, averaging_interval));
686+
687+
return Py_BuildValue(
688+
"(ddd)(ddd)",
689+
velocity_stamped.velocity.linear.x, velocity_stamped.velocity.linear.y,
690+
velocity_stamped.velocity.linear.z,
691+
velocity_stamped.velocity.angular.x, velocity_stamped.velocity.angular.y,
692+
velocity_stamped.velocity.angular.z);
673693
}
674-
*/
694+
675695
static inline int checkTranslationType(PyObject * o)
676696
{
677697
PyTypeObject * translation_type =
@@ -1058,8 +1078,8 @@ static struct PyMethodDef buffer_core_methods[] =
10581078
nullptr},
10591079
{"lookup_transform_full_core", (PyCFunction)lookupTransformFullCore, METH_VARARGS | METH_KEYWORDS,
10601080
nullptr},
1061-
// {"lookupTwistCore", (PyCFunction)lookupTwistCore, METH_VARARGS | METH_KEYWORDS},
1062-
// {"lookupTwistFullCore", lookupTwistFullCore, METH_VARARGS},
1081+
{"lookupVelocityCore", (PyCFunction)lookupVelocityCore, METH_VARARGS | METH_KEYWORDS, nullptr},
1082+
{"lookupVelocityFullCore", lookupVelocityFullCore, METH_VARARGS, nullptr},
10631083
{nullptr, nullptr, 0, nullptr}
10641084
};
10651085

0 commit comments

Comments
 (0)