Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft: Break geometry_msgs dependency in tf2 #732

Draft
wants to merge 10 commits into
base: rolling
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
72 changes: 37 additions & 35 deletions test_tf2/test/buffer_core_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/


#if _WIN32
#define _USE_MATH_DEFINES
#endif
Expand All @@ -52,7 +53,7 @@
#include <tf2_ros/buffer_interface.h>

#include "permuter.hpp"

#ifdef FIX_SETTRANSFORM
void seed_rand()
{
//Seed random number generator with current time.
Expand Down Expand Up @@ -306,7 +307,7 @@ TEST(BufferCore_setTransform, NoInsertOnSelfTransform)
tf2::BufferCore mBC;
geometry_msgs::msg::TransformStamped tranStamped;
setIdentity(tranStamped.transform);
tranStamped.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.stamp = tf2::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.frame_id = "same_frame";
tranStamped.child_frame_id = "same_frame";
EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
Expand All @@ -317,7 +318,7 @@ TEST(BufferCore_setTransform, NoInsertWithNan)
tf2::BufferCore mBC;
geometry_msgs::msg::TransformStamped tranStamped;
setIdentity(tranStamped.transform);
tranStamped.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.stamp = tf2::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.frame_id = "same_frame";
tranStamped.child_frame_id = "other_frame";
EXPECT_TRUE(mBC.setTransform(tranStamped, "authority"));
Expand All @@ -331,7 +332,7 @@ TEST(BufferCore_setTransform, NoInsertWithNoFrameID)
tf2::BufferCore mBC;
geometry_msgs::msg::TransformStamped tranStamped;
setIdentity(tranStamped.transform);
tranStamped.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.stamp = tf2::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.frame_id = "same_frame";
tranStamped.child_frame_id = "";
EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
Expand All @@ -345,7 +346,7 @@ TEST(BufferCore_setTransform, NoInsertWithNoParentID)
tf2::BufferCore mBC;
geometry_msgs::msg::TransformStamped tranStamped;
setIdentity(tranStamped.transform);
tranStamped.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.stamp = tf2::toMsg(tf2::timeFromSec(10.0));
tranStamped.header.frame_id = "";
tranStamped.child_frame_id = "some_frame";
EXPECT_FALSE(mBC.setTransform(tranStamped, "authority"));
Expand Down Expand Up @@ -636,9 +637,9 @@ TEST(BufferCore_lookupTransform, i_configuration)

rostest::Permuter permuter;
std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand All @@ -664,7 +665,7 @@ TEST(BufferCore_lookupTransform, i_configuration)
setupTree(mBC, "i", eval_time, interpolation_space);

geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

EXPECT_EQ(outpose.header.stamp, eval_time);
Expand Down Expand Up @@ -898,9 +899,9 @@ TEST(BufferCore_lookupTransform, one_link_configuration)
rostest::Permuter permuter;

std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand All @@ -926,7 +927,7 @@ TEST(BufferCore_lookupTransform, one_link_configuration)
setupTree(mBC, "1", eval_time, interpolation_space);

geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

EXPECT_TRUE(check_1_result(outpose, source_frame, target_frame, eval_time, epsilon));
Expand All @@ -941,9 +942,9 @@ TEST(BufferCore_lookupTransform, v_configuration)
rostest::Permuter permuter;

std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand Down Expand Up @@ -972,7 +973,7 @@ TEST(BufferCore_lookupTransform, v_configuration)
setupTree(mBC, "v", eval_time, interpolation_space);

geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

EXPECT_TRUE(check_v_result(outpose, source_frame, target_frame, eval_time, epsilon));
Expand All @@ -987,9 +988,9 @@ TEST(BufferCore_lookupTransform, y_configuration)
rostest::Permuter permuter;

std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand Down Expand Up @@ -1018,7 +1019,7 @@ TEST(BufferCore_lookupTransform, y_configuration)
setupTree(mBC, "y", eval_time, interpolation_space);

geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

EXPECT_TRUE(check_y_result(outpose, source_frame, target_frame, eval_time, epsilon));
Expand All @@ -1032,9 +1033,9 @@ TEST(BufferCore_lookupTransform, multi_configuration)
rostest::Permuter permuter;

std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand Down Expand Up @@ -1064,9 +1065,9 @@ TEST(BufferCore_lookupTransform, multi_configuration)
tf2::BufferCore mBC;
setupTree(mBC, "1_v", eval_time, interpolation_space);

if (mBC.canTransform(source_frame, target_frame, tf2_ros::fromMsg(eval_time))) {
if (mBC.canTransform(source_frame, target_frame, tf2::fromMsg(eval_time))) {
geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

if ((source_frame == "1" || source_frame == "2") &&
Expand Down Expand Up @@ -1377,9 +1378,9 @@ TEST(BufferCore_lookupTransform, ring_45_configuration)
rostest::Permuter permuter;

std::vector<builtin_interfaces::msg::Time> times;
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2_ros::toMsg(tf2::timeFromSec(0.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(1.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(10.0)));
times.push_back(tf2::toMsg(tf2::timeFromSec(0.0)));
builtin_interfaces::msg::Time eval_time;
permuter.addOptionSet(times, &eval_time);

Expand Down Expand Up @@ -1420,7 +1421,7 @@ TEST(BufferCore_lookupTransform, ring_45_configuration)
setupTree(mBC, "ring_45", eval_time, interpolation_space);

geometry_msgs::msg::TransformStamped outpose = mBC.lookupTransform(
source_frame, target_frame, tf2_ros::fromMsg(
source_frame, target_frame, tf2::fromMsg(
eval_time));

EXPECT_EQ(outpose.header.stamp, eval_time);
Expand Down Expand Up @@ -1669,7 +1670,7 @@ TEST(BufferCore_lookupTransform, invalid_arguments)
std::chrono::seconds(0) +
std::chrono::nanoseconds(0));

setupTree(mBC, "i", tf2_ros::toMsg(tf2::timeFromSec(1.0)));
setupTree(mBC, "i", tf2::toMsg(tf2::timeFromSec(1.0)));

// EXPECT_NO_THROW
EXPECT_NO_THROW(mBC.lookupTransform("b", "a", eval_time_time_point));
Expand All @@ -1692,7 +1693,7 @@ TEST(BufferCore_canTransform, invalid_arguments)
std::chrono::seconds(0) +
std::chrono::nanoseconds(0));

setupTree(mBC, "i", tf2_ros::toMsg(tf2::timeFromSec(1.0)));
setupTree(mBC, "i", tf2::toMsg(tf2::timeFromSec(1.0)));

EXPECT_TRUE(mBC.canTransform("b", "a", eval_time_time_point));

Expand Down Expand Up @@ -1736,7 +1737,7 @@ TEST(BufferCore_transformableCallbacks, alreadyTransformable)
TransformableHelper h;

geometry_msgs::msg::TransformStamped t;
t.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(1.0));
t.header.stamp = tf2::toMsg(tf2::timeFromSec(1.0));
t.header.frame_id = "a";
t.child_frame_id = "b";
t.transform.rotation.w = 1.0;
Expand Down Expand Up @@ -1779,7 +1780,7 @@ TEST(BufferCore_transformableCallbacks, waitForNewTransform)

geometry_msgs::msg::TransformStamped t;
for (uint32_t i = 1; i <= 10; ++i) {
t.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(i));
t.header.stamp = tf2::toMsg(tf2::timeFromSec(i));
t.header.frame_id = "a";
t.child_frame_id = "b";
t.transform.rotation.w = 1.0;
Expand Down Expand Up @@ -1814,7 +1815,7 @@ TEST(BufferCore_transformableCallbacks, waitForOldTransform)

geometry_msgs::msg::TransformStamped t;
for (uint32_t i = 10; i > 0; --i) {
t.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(i));
t.header.stamp = tf2::toMsg(tf2::timeFromSec(i));
t.header.frame_id = "a";
t.child_frame_id = "b";
t.transform.rotation.w = 1.0;
Expand Down Expand Up @@ -2782,6 +2783,7 @@ TEST(tf2_stamped, OperatorEqual)

}
*/
#endif
int main(int argc, char ** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down
16 changes: 8 additions & 8 deletions test_tf2/test/test_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ TEST(MessageFilter, noTransforms)

std::shared_ptr<geometry_msgs::msg::PointStamped> msg =
std::make_shared<geometry_msgs::msg::PointStamped>();
msg->header.stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
msg->header.stamp = tf2::toMsg(tf2::timeFromSec(1));
msg->header.frame_id = "frame2";
filter.add(msg);

Expand All @@ -115,7 +115,7 @@ TEST(MessageFilter, noTransformsSameFrame)

std::shared_ptr<geometry_msgs::msg::PointStamped> msg =
std::make_shared<geometry_msgs::msg::PointStamped>();
msg->header.stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
msg->header.stamp = tf2::toMsg(tf2::timeFromSec(1));
msg->header.frame_id = "frame1";
filter.add(msg);

Expand Down Expand Up @@ -157,7 +157,7 @@ TEST(MessageFilter, preexistingTransforms)

filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));
buffer.setTransform(
createTransform(
tf2::Quaternion(0, 0, 0, 1), tf2::Vector3(1, 2, 3), stamp,
Expand Down Expand Up @@ -188,7 +188,7 @@ TEST(MessageFilter, postTransforms)

filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));

builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));

std::shared_ptr<geometry_msgs::msg::PointStamped> msg =
std::make_shared<geometry_msgs::msg::PointStamped>();
Expand Down Expand Up @@ -218,7 +218,7 @@ TEST(MessageFilter, concurrentTransforms)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);

builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));

std::shared_ptr<geometry_msgs::msg::PointStamped> msg =
std::make_shared<geometry_msgs::msg::PointStamped>();
Expand Down Expand Up @@ -270,7 +270,7 @@ TEST(MessageFilter, concurrentTransforms)
// filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
// // filter.registerFailureCallback(std::bind(&Notification::failure, &n, std::placeholders::_1, std::placeholders::_2));
//
// builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
// builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));
//
// for (int i = 0; i < 20; ++i)
// {
Expand Down Expand Up @@ -306,7 +306,7 @@ TEST(MessageFilter, setTargetFrame)
filter.registerCallback(std::bind(&Notification::notify, &n, std::placeholders::_1));
filter.setTargetFrame("frame1000");

builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));
buffer.setTransform(
createTransform(
tf2::Quaternion(0, 0, 0, 1), tf2::Vector3(1, 2, 3), stamp,
Expand Down Expand Up @@ -341,7 +341,7 @@ TEST(MessageFilter, multipleTargetFrames)
target_frames.push_back("frame2");
filter.setTargetFrames(target_frames);

builtin_interfaces::msg::Time stamp = tf2_ros::toMsg(tf2::timeFromSec(1));
builtin_interfaces::msg::Time stamp = tf2::toMsg(tf2::timeFromSec(1));
buffer.setTransform(
createTransform(
tf2::Quaternion(0, 0, 0, 1), tf2::Vector3(1, 2, 3), stamp,
Expand Down
4 changes: 2 additions & 2 deletions test_tf2/test/test_static_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ TEST(StaticTransformPublisher, a_d_different_times)
geometry_msgs::msg::TransformStamped ts;
ts.transform.rotation.w = 1;
ts.header.frame_id = "c";
ts.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10));
ts.header.stamp = tf2::toMsg(tf2::timeFromSec(10));
ts.child_frame_id = "d";

// make sure listener has populated
Expand Down Expand Up @@ -198,7 +198,7 @@ TEST(StaticTransformPublisher, multiple_parent_test)
geometry_msgs::msg::TransformStamped ts;
ts.transform.rotation.w = 1;
ts.header.frame_id = "c";
ts.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(10));
ts.header.stamp = tf2::toMsg(tf2::timeFromSec(10));
ts.child_frame_id = "d";

stb.sendTransform(ts);
Expand Down
2 changes: 1 addition & 1 deletion test_tf2/test/test_tf2_bullet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ int main(int argc, char ** argv)
t.transform.rotation.x = 1;
t.transform.rotation.y = 0;
t.transform.rotation.z = 0;
t.header.stamp = tf2_ros::toMsg(tf2::timeFromSec(2));
t.header.stamp = tf2::toMsg(tf2::timeFromSec(2));
t.header.frame_id = "A";
t.child_frame_id = "B";
tf_buffer->setTransform(t, "test");
Expand Down
Loading