11/*
2- * Copyright (C) 2018 Open Source Robotics Foundation
2+ * Copyright (C) 2024 Open Source Robotics Foundation
33 *
44 * Licensed under the Apache License, Version 2.0 (the "License");
55 * you may not use this file except in compliance with the License.
1717
1818#include < gtest/gtest.h>
1919
20+ #include < string>
21+ #include < vector>
22+ #include < functional>
23+ #include < thread>
24+
2025#include < gz/msgs/odometry.pb.h>
2126#include < gz/msgs/pose_v.pb.h>
2227#include < gz/msgs/twist.pb.h>
2328
2429#include < gz/common/Console.hh>
2530#include < gz/common/Util.hh>
2631#include < gz/math/Pose3.hh>
32+ #include < gz/math/Vector3.hh>
2733#include < gz/transport/Node.hh>
2834#include < gz/utils/ExtraTestMacros.hh>
2935
36+
3037#include " gz/sim/components/Name.hh"
38+ #include " test_config.hh"
39+
3140#include " gz/sim/components/Model.hh"
3241#include " gz/sim/components/Pose.hh"
3342#include " gz/sim/Server.hh"
34- #include " gz/sim/SystemLoader.hh"
35- #include " test_config.hh"
3643
3744#include " ../helpers/Relay.hh"
3845#include " ../helpers/EnvTestFixture.hh"
@@ -53,11 +60,13 @@ class MecanumDriveTest : public InternalFixture<::testing::TestWithParam<int>>
5360 const std::string &_cmdVelTopic,
5461 const std::string &_odomTopic)
5562 {
56- // / \param[in] forward If forward is true, the 'max_acceleration'
57- // and 'max_velocity' properties are tested, as the movement
58- // is forward, otherwise 'min_acceleration' and 'min_velocity'
59- // properties are tested.
60- auto testCmdVel = [&](bool forward){
63+ // / \param[in] fb_component forward/backward motion vector component.
64+ // / \param[in] lr_component left/right motion vector component.
65+ // / \param[in] yaw_component yaw rotation component.
66+ auto testCmdVel = [&](double fb_component,
67+ double lr_component,
68+ double yaw_component)
69+ {
6170 // Start server
6271 ServerConfig serverConfig;
6372 serverConfig.SetSdfFile (_sdfFile);
@@ -125,19 +134,22 @@ class MecanumDriveTest : public InternalFixture<::testing::TestWithParam<int>>
125134 // Avoid wheel slip by limiting acceleration (1 m/s^2)
126135 // and max velocity (0.5 m/s).
127136 // See <max_velocity> and <max_aceleration> parameters
128- // in "/test/worlds/diff_drive .sdf".
137+ // in "/test/worlds/mecanum_drive .sdf".
129138 // See <min_velocity>, <min_aceleration>, <min_jerk> and
130- // <max_jerk> parameters in "/test/worlds/diff_drive .sdf".
139+ // <max_jerk> parameters in "/test/worlds/mecanum_drive .sdf".
131140 test::Relay velocityRamp;
132- const int movementDirection = (forward ? 1 : -1 );
133- double desiredLinVelX = movementDirection * 0.15 ;
134- double desiredLinVelY = movementDirection * 0.15 ;
141+ double desiredLinVelX = fb_component;
142+ double desiredLinVelY = lr_component;
143+ double desiredAngVel = yaw_component;
144+
135145 velocityRamp.OnPreUpdate (
136146 [&](const UpdateInfo &/* _info*/ ,
137147 const EntityComponentManager &)
138148 {
139149 msgs::Set (msg.mutable_linear (),
140150 math::Vector3d (desiredLinVelX, desiredLinVelY, 0 ));
151+ msgs::Set (msg.mutable_angular (),
152+ math::Vector3d (0.0 , 0 , desiredAngVel));
141153 pub.Publish (msg);
142154 });
143155
@@ -165,84 +177,109 @@ class MecanumDriveTest : public InternalFixture<::testing::TestWithParam<int>>
165177 // change. To find the final pose of the model, we have to do the
166178 // following similarity transformation
167179
168- math::Pose3d tOdomModel (0.554283 ,0 ,- 0.325 ,0 ,0 ,0 );
180+ math::Pose3d tOdomModel (- 0.2 ,0 ,0 ,0 ,0 ,0 );
169181 auto finalModelFramePose =
170182 tOdomModel * odomPoses.back () * tOdomModel.Inverse ();
171183
172184 // Odom for 3s
173185 ASSERT_FALSE (odomPoses.empty ());
174186 EXPECT_EQ (150u , odomPoses.size ());
175187
176- auto expectedLowerPosition =
177- (forward ? poses[0 ].Pos () : poses[3999 ].Pos ());
178- auto expectedGreaterPosition =
179- (forward ? poses[3999 ].Pos () : poses[0 ].Pos ());
188+ auto relativeMotionPos = poses[3999 ].Pos () - poses[0 ].Pos ();
189+ auto relativeMotionRot = poses[3999 ].Rot ().Yaw () - poses[0 ].Rot ().Yaw ();
190+
191+ // if the linear motion is non-zero
192+ // the vehicle should move in the commanded direction
193+ if (std::abs (fb_component) > 0.0 || std::abs (lr_component) > 0.0 )
194+ {
195+ auto cmdVelDir = math::Vector2 (desiredLinVelX,
196+ desiredLinVelY).Normalized ();
197+ auto motionDir = math::Vector2 (relativeMotionPos.X (),
198+ relativeMotionPos.Y ()).Normalized ();
199+ auto scalarProjection = cmdVelDir.Dot (motionDir);
200+ EXPECT_GT (motionDir.Length (), 0.5 ); // is there motion?
201+ EXPECT_GT (scalarProjection, 0.9 ); // is it in the right direction?
202+
203+ // Verify velocity and acceleration upper boundaries.
204+ double t = 3.0 ;
205+ double d = poses[3999 ].Pos ().Distance (poses[0 ].Pos ());
206+ double v0 = 0 ;
207+ double v = d / t;
208+ double a = (v - v0) / t;
209+
210+ // The vehicle should not exceed the max velocity and acceleration
211+ // notice the limits for the x and y direction are separately
212+ // enforced
213+ auto threshold_factor = math::Vector2 (fb_component,
214+ lr_component).Length ();
215+
216+ EXPECT_LT (v, 0.5 * threshold_factor);
217+ EXPECT_LT (a, 1.0 * threshold_factor);
218+ EXPECT_GT (v, -0.5 * threshold_factor);
219+ EXPECT_GT (a, -1.0 * threshold_factor);
220+ }
180221
181- EXPECT_LT (expectedLowerPosition. X (), expectedGreaterPosition. X ());
182- EXPECT_LT (expectedLowerPosition. Y (), expectedGreaterPosition. Y ());
183- EXPECT_NEAR (expectedLowerPosition. Z (), expectedGreaterPosition. Z (), tol);
184- EXPECT_NEAR (poses[ 0 ]. Rot (). X (), poses[ 3999 ]. Rot (). X (), tol);
185- EXPECT_NEAR (poses[ 0 ]. Rot (). Y (), poses[ 3999 ]. Rot (). Y (), tol );
186- EXPECT_NEAR (poses[ 0 ]. Rot (). Z (), poses[ 3999 ]. Rot (). Z (), tol);
222+ // The vehicle should rotate in the commanded direction
223+ if ( std::abs (yaw_component) > 0.0 )
224+ {
225+ // the relative rotation has the same sign as the commanded rotation
226+ EXPECT_GT (desiredAngVel * relativeMotionRot, 0.0 );
227+ }
187228
188229 // The value from odometry will be close, but not exactly the ground truth
189230 // pose of the robot model. This is partially due to throttling the
190- // odometry publisher, partially due to a frame difference between the
191- // odom frame and the model frame, and partially due to wheel slip.
192- EXPECT_NEAR (poses.back ().Pos ().X (), odomPoses.back ().Pos ().X (), 1e-2 );
193- EXPECT_NEAR (poses.back ().Pos ().Y (), odomPoses.back ().Pos ().Y (), 1e-2 );
194- // EXPECT_NEAR(poses.back().Pos().X(), finalModelFramePose.Pos().X(), 1e-2);
195- // EXPECT_NEAR(poses.back().Pos().Y(), finalModelFramePose.Pos().Y(), 1e-2);
196-
197- // Verify velocity and acceleration boundaries.
198- // Moving time.
199- double t = 3.0 ;
200- double d = poses[3999 ].Pos ().Distance (poses[0 ].Pos ());
201- double v0 = 0 ;
202- double v = d / t;
203- double a = (v - v0) / t;
204-
205- EXPECT_LT (v, 0.5 );
206- EXPECT_LT (a, 1 );
207- EXPECT_GT (v, -0.5 );
208- EXPECT_GT (a, -1 );
231+ // odometry publisher, and partially due to wheel slip.
232+ EXPECT_NEAR (poses[1020 ].Pos ().X (), odomPoses[0 ].Pos ().X (), 1e-2 );
233+ EXPECT_NEAR (poses[1020 ].Pos ().Y (), odomPoses[0 ].Pos ().Y (), 1e-2 );
234+ EXPECT_NEAR (poses.back ().Pos ().X (), finalModelFramePose.Pos ().X (), 1e-2 );
235+ EXPECT_NEAR (poses.back ().Pos ().Y (), finalModelFramePose.Pos ().Y (), 1e-2 );
236+
209237
210238 };
211239
212- testCmdVel (true /* test forward movement*/ );
213- testCmdVel (false /* test backward movement*/ );
240+ testCmdVel (0 ., 0 ., 0 .); /* no motion */
241+
242+ testCmdVel (+1 ., 0 ., 0 .); /* pure forward */
243+ testCmdVel (-1 ., 0 ., 0 .); /* pure backward */
244+ testCmdVel (0 ., +1 ., 0 .); /* pure left */
245+ testCmdVel (0 ., -1 ., 0 .); /* pure right */
246+
247+ testCmdVel (+1 ., +1 ., 0 .); /* forward left */
248+ testCmdVel (+1 ., -1 ., 0 .); /* forward right */
249+ testCmdVel (-1 ., +1 ., 0 .); /* backward left */
250+ testCmdVel (-1 ., -1 ., 0 .); /* backward right */
251+
252+ testCmdVel (0 ., 0 ., +0.1 ); /* CW motion */
253+ testCmdVel (0 ., 0 ., -0.1 ); /* CCW motion */
214254 }
215255};
216256
217257// ///////////////////////////////////////////////
218- // See: https://github.com/gazebosim/gz-sim/issues/1175
219- // See: https://github.com/gazebosim/gz-sim/issues/630
220258TEST_P (MecanumDriveTest, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCmd))
221259{
222- TestPublishCmd (
223- std::string (PROJECT_SOURCE_PATH) + " /test/worlds/mecanum_drive.sdf" ,
260+ TestPublishCmd (common::joinPaths (
261+ std::string (PROJECT_SOURCE_PATH) + " /test/worlds/mecanum_drive.sdf" ) ,
224262 " /model/vehicle_blue/cmd_vel" , " /model/vehicle_blue/odometry" );
225263}
226264
227265// ///////////////////////////////////////////////
228- // See: https://github.com/gazebosim/gz-sim/issues/630
229266TEST_P (MecanumDriveTest,
230267 GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX (PublishCmdCustomTopics))
231268{
232- TestPublishCmd (
269+ TestPublishCmd (common::joinPaths (
233270 std::string (PROJECT_SOURCE_PATH) +
234- " /test/worlds/mecanum_drive_custom_topics.sdf" ,
271+ " /test/worlds/mecanum_drive_custom_topics.sdf" ) ,
235272 " /model/foo/cmdvel" , " /model/bar/odom" );
236273}
237274
238275
239- // ///////////////////////////////////////////////
276+ // // ///////////////////////////////////////////////
240277TEST_P (MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(OdomFrameId))
241278{
242279 // Start server
243280 ServerConfig serverConfig;
244- serverConfig.SetSdfFile (std::string (PROJECT_SOURCE_PATH) +
245- " /test/worlds/mecanum_drive.sdf" );
281+ serverConfig.SetSdfFile (common::joinPaths ( std::string (PROJECT_SOURCE_PATH) +
282+ " /test/worlds/mecanum_drive.sdf" )) ;
246283
247284 Server server (serverConfig);
248285 EXPECT_FALSE (server.Running ());
@@ -294,13 +331,13 @@ TEST_P(MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(OdomFrameId))
294331 EXPECT_EQ (5u , odomPosesCount);
295332}
296333
297- // ///////////////////////////////////////////////
334+ // // ///////////////////////////////////////////////
298335TEST_P (MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(OdomCustomFrameId))
299336{
300337 // Start server
301338 ServerConfig serverConfig;
302- serverConfig.SetSdfFile (std::string (PROJECT_SOURCE_PATH) +
303- " /test/worlds/mecanum_drive_custom_frame_id.sdf" );
339+ serverConfig.SetSdfFile (common::joinPaths ( std::string (PROJECT_SOURCE_PATH) +
340+ " /test/worlds/mecanum_drive_custom_frame_id.sdf" )) ;
304341
305342 Server server (serverConfig);
306343 EXPECT_FALSE (server.Running ());
@@ -356,8 +393,8 @@ TEST_P(MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Pose_VFrameId))
356393{
357394 // Start server
358395 ServerConfig serverConfig;
359- serverConfig.SetSdfFile (std::string (PROJECT_SOURCE_PATH) +
360- " /test/worlds/mecanum_drive.sdf" );
396+ serverConfig.SetSdfFile (common::joinPaths ( std::string (PROJECT_SOURCE_PATH) +
397+ " /test/worlds/mecanum_drive.sdf" )) ;
361398
362399 Server server (serverConfig);
363400 EXPECT_FALSE (server.Running ());
@@ -416,8 +453,8 @@ TEST_P(MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Pose_VCustomFrameId))
416453{
417454 // Start server
418455 ServerConfig serverConfig;
419- serverConfig.SetSdfFile (std::string (PROJECT_SOURCE_PATH) +
420- " /test/worlds/mecanum_drive_custom_frame_id.sdf" );
456+ serverConfig.SetSdfFile (common::joinPaths ( std::string (PROJECT_SOURCE_PATH) +
457+ " /test/worlds/mecanum_drive_custom_frame_id.sdf" )) ;
421458
422459 Server server (serverConfig);
423460 EXPECT_FALSE (server.Running ());
@@ -476,8 +513,8 @@ TEST_P(MecanumDriveTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(Pose_VCustomTfTopic))
476513{
477514 // Start server
478515 ServerConfig serverConfig;
479- serverConfig.SetSdfFile (std::string (PROJECT_SOURCE_PATH) +
480- " /test/worlds/mecanum_drive_custom_tf_topic.sdf" );
516+ serverConfig.SetSdfFile (common::joinPaths ( std::string (PROJECT_SOURCE_PATH) +
517+ " /test/worlds/mecanum_drive_custom_tf_topic.sdf" )) ;
481518
482519 Server server (serverConfig);
483520 EXPECT_FALSE (server.Running ());
0 commit comments