Skip to content

Commit ed50b69

Browse files
Update test_diff_drive_controller.cpp
1 parent 384e2f1 commit ed50b69

File tree

1 file changed

+0
-75
lines changed

1 file changed

+0
-75
lines changed

diff_drive_controller/test/test_diff_drive_controller.cpp

Lines changed: 0 additions & 75 deletions
Original file line numberDiff line numberDiff line change
@@ -1221,80 +1221,6 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war
12211221
executor.cancel();
12221222
}
12231223

1224-
<<<<<<< HEAD
1225-
=======
1226-
TEST_F(TestDiffDriveController, odometry_set_service)
1227-
{
1228-
// 0. Initialize and activate the controller
1229-
ASSERT_EQ(
1230-
InitController(
1231-
left_wheel_names, right_wheel_names,
1232-
{rclcpp::Parameter("wheel_separation", 0.4), rclcpp::Parameter("wheel_radius", 1.0)}),
1233-
controller_interface::return_type::OK);
1234-
1235-
rclcpp::executors::SingleThreadedExecutor executor;
1236-
executor.add_node(controller_->get_node()->get_node_base_interface());
1237-
1238-
auto state = controller_->configure();
1239-
assignResourcesPosFeedback();
1240-
1241-
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
1242-
EXPECT_EQ(0.01, left_wheel_vel_cmd_->get_optional().value());
1243-
EXPECT_EQ(0.02, right_wheel_vel_cmd_->get_optional().value());
1244-
1245-
state = controller_->get_node()->activate();
1246-
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
1247-
1248-
rclcpp::Time test_time(0, 0, RCL_ROS_TIME);
1249-
rclcpp::Duration period = rclcpp::Duration::from_seconds(0.1);
1250-
1251-
// 1. Move the robot first
1252-
publish(1.0, 0.0);
1253-
controller_->wait_for_twist(executor);
1254-
controller_->update(test_time, period);
1255-
test_time += period;
1256-
1257-
// verify initial movement
1258-
ASSERT_GT(controller_->odometry_.getX(), 0.0);
1259-
1260-
// 2. Stop and call odom set service
1261-
publish(0.0, 0.0);
1262-
controller_->wait_for_twist(executor);
1263-
auto set_request = std::make_shared<control_msgs::srv::SetOdometry::Request>();
1264-
auto set_response = std::make_shared<control_msgs::srv::SetOdometry::Response>();
1265-
set_request->x = 5.0;
1266-
set_request->y = -2.0;
1267-
set_request->yaw = 1.57079632679; // 90 degrees
1268-
controller_->set_odometry(nullptr, set_request, set_response);
1269-
EXPECT_TRUE(set_response->success);
1270-
1271-
// run update to process and verify odom values
1272-
controller_->update(test_time, period);
1273-
test_time += period;
1274-
EXPECT_NEAR(controller_->odometry_.getX(), 5.0, 1e-6);
1275-
EXPECT_NEAR(controller_->odometry_.getY(), -2.0, 1e-6);
1276-
EXPECT_NEAR(controller_->odometry_.getHeading(), 1.57079632679, 1e-5); // 90 deg
1277-
1278-
// 3. Move again to ensure it still works
1279-
publish(1.0, 0.0); // we move in Y now
1280-
controller_->wait_for_twist(executor);
1281-
1282-
// simulate the movement by updating the position feedback
1283-
position_values_[0] += 0.1; // left wheel moved
1284-
position_values_[1] += 0.1; // right wheel moved
1285-
controller_->update(test_time, period);
1286-
test_time += period;
1287-
EXPECT_GT(controller_->odometry_.getY(), -2.0);
1288-
1289-
// 4. Deactivate and cleanup
1290-
std::this_thread::sleep_for(std::chrono::milliseconds(300));
1291-
state = controller_->get_node()->deactivate();
1292-
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
1293-
state = controller_->get_node()->cleanup();
1294-
ASSERT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED);
1295-
executor.cancel();
1296-
}
1297-
12981224
TEST_F(TestDiffDriveController, test_open_loop_odometry_with_clamped_input)
12991225
{
13001226
const double max_linear_vel = 0.5;
@@ -1422,7 +1348,6 @@ TEST_F(TestDiffDriveController, test_open_loop_odometry_with_unclamped_input)
14221348
executor.cancel();
14231349
}
14241350

1425-
>>>>>>> 6c1299f (Added test for open-loop odometry with clamped input (#2280))
14261351
int main(int argc, char ** argv)
14271352
{
14281353
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)