Skip to content

Commit 92dc339

Browse files
committed
Removed unused params, added unclamped tests
1 parent 9ac6b7d commit 92dc339

File tree

1 file changed

+61
-2
lines changed

1 file changed

+61
-2
lines changed

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 61 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1258,9 +1258,7 @@ TEST_F(TestDiffDriveController, test_open_loop_odometry_with_clamped_input)
12581258
InitController(
12591259
left_wheel_names, right_wheel_names,
12601260
{rclcpp::Parameter("open_loop", rclcpp::ParameterValue(true)),
1261-
rclcpp::Parameter("linear.x.has_velocity_limits", rclcpp::ParameterValue(true)),
12621261
rclcpp::Parameter("linear.x.max_velocity", rclcpp::ParameterValue(max_linear_vel)),
1263-
rclcpp::Parameter("angular.z.has_velocity_limits", rclcpp::ParameterValue(true)),
12641262
rclcpp::Parameter("angular.z.max_velocity", rclcpp::ParameterValue(max_angular_vel))}),
12651263
controller_interface::return_type::OK);
12661264

@@ -1316,6 +1314,67 @@ TEST_F(TestDiffDriveController, test_open_loop_odometry_with_clamped_input)
13161314
executor.cancel();
13171315
}
13181316

1317+
TEST_F(TestDiffDriveController, test_open_loop_odometry_with_unclamped_input)
1318+
{
1319+
// Initialize the controller with open_loop enabled without velocity limits
1320+
ASSERT_EQ(
1321+
InitController(
1322+
left_wheel_names, right_wheel_names,
1323+
{rclcpp::Parameter("open_loop", rclcpp::ParameterValue(true))}),
1324+
controller_interface::return_type::OK);
1325+
1326+
rclcpp::executors::SingleThreadedExecutor executor;
1327+
executor.add_node(controller_->get_node()->get_node_base_interface());
1328+
1329+
auto state = controller_->configure();
1330+
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
1331+
1332+
assignResourcesNoFeedback();
1333+
1334+
state = controller_->get_node()->activate();
1335+
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
1336+
1337+
waitForSetup(executor);
1338+
1339+
const double dt = 0.1;
1340+
1341+
// Test Linear
1342+
const double commanded_linear = 5.0;
1343+
publish(commanded_linear, 0.0);
1344+
controller_->wait_for_twist(executor);
1345+
1346+
ASSERT_EQ(
1347+
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)),
1348+
controller_interface::return_type::OK);
1349+
1350+
// Odometry should exactly reflect the commanded linear velocity
1351+
EXPECT_NEAR(controller_->odometry_.getLinear(), commanded_linear, 1e-3);
1352+
1353+
// Verify that the position integration uses the commanded value (5.0 * 0.1s = 0.5m)
1354+
EXPECT_NEAR(controller_->odometry_.getX(), commanded_linear * dt, 1e-3);
1355+
1356+
// Test Angular
1357+
const double commanded_angular = 5.0;
1358+
publish(0.0, commanded_angular);
1359+
controller_->wait_for_twist(executor);
1360+
1361+
ASSERT_EQ(
1362+
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)),
1363+
controller_interface::return_type::OK);
1364+
1365+
// Verify the angular velocity and heading integration use the commanded value
1366+
EXPECT_NEAR(controller_->odometry_.getAngular(), commanded_angular, 1e-3);
1367+
EXPECT_NEAR(controller_->odometry_.getHeading(), commanded_angular * dt, 1e-3);
1368+
1369+
// Safely spin down the lifecycle
1370+
std::this_thread::sleep_for(std::chrono::milliseconds(300));
1371+
state = controller_->get_node()->deactivate();
1372+
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
1373+
state = controller_->get_node()->cleanup();
1374+
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
1375+
executor.cancel();
1376+
}
1377+
13191378
int main(int argc, char ** argv)
13201379
{
13211380
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)