Skip to content

Commit b333def

Browse files
authored
[mecanum_drive_controller] Fix Odometry Initialization (#1573)
1 parent 1a38b35 commit b333def

File tree

5 files changed

+119
-0
lines changed

5 files changed

+119
-0
lines changed

mecanum_drive_controller/include/mecanum_drive_controller/odometry.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,11 @@ class Odometry
6868
;
6969
}
7070

71+
const std::array<double, PLANAR_POINT_DIM> & getBaseFrameOffset() const
72+
{
73+
return base_frame_offset_;
74+
}
75+
7176
/// \brief Sets the wheels parameters: mecanum geometric param and radius
7277
/// \param sum_of_robot_center_projection_on_X_Y_axis Wheels geometric param
7378
/// (used in mecanum wheels' ik) [m]

mecanum_drive_controller/src/mecanum_drive_controller.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,12 @@ controller_interface::CallbackReturn MecanumDriveController::on_configure(
107107
REAR_LEFT, params_.rear_left_wheel_command_joint_name,
108108
params_.rear_left_wheel_state_joint_name);
109109

110+
// Initialize odometry
111+
std::array<double, PLANAR_POINT_DIM> base_frame_offset = {
112+
{params_.kinematics.base_frame_offset.x, params_.kinematics.base_frame_offset.y,
113+
params_.kinematics.base_frame_offset.theta}};
114+
odometry_.init(get_node()->now(), base_frame_offset);
115+
110116
// Set wheel params for the odometry computation
111117
odometry_.setWheelsParams(
112118
params_.kinematics.sum_of_robot_center_projection_on_X_Y_axis,

mecanum_drive_controller/test/mecanum_drive_controller_params.yaml

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,3 +17,24 @@ test_mecanum_drive_controller:
1717
enable_odom_tf: true
1818
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
1919
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
20+
21+
22+
test_mecanum_drive_controller_with_rotation:
23+
ros__parameters:
24+
reference_timeout: 5.0
25+
26+
front_left_wheel_command_joint_name: "front_left_wheel_joint"
27+
front_right_wheel_command_joint_name: "front_right_wheel_joint"
28+
rear_right_wheel_command_joint_name: "rear_right_wheel_joint"
29+
rear_left_wheel_command_joint_name: "rear_left_wheel_joint"
30+
31+
kinematics:
32+
base_frame_offset: { x: 1.0, y: 2.0, theta: 3.0 }
33+
wheels_radius: 0.05
34+
sum_of_robot_center_projection_on_X_Y_axis: 0.2925
35+
36+
base_frame_id: "base_link"
37+
odom_frame_id: "odom"
38+
enable_odom_tf: true
39+
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
40+
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001]

mecanum_drive_controller/test/test_mecanum_drive_controller.cpp

Lines changed: 86 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -562,6 +562,92 @@ TEST_F(
562562
EXPECT_EQ((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z, 0.0);
563563
}
564564

565+
TEST_F(MecanumDriveControllerTest, SideToSideAndRotationOdometryTest)
566+
{
567+
// Initialize controller
568+
SetUpController("test_mecanum_drive_controller_with_rotation");
569+
570+
// Configure
571+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
572+
573+
// Check on the base frame offset is set by the params
574+
EXPECT_EQ(controller_->odometry_.getBaseFrameOffset()[0], 1.0);
575+
EXPECT_EQ(controller_->odometry_.getBaseFrameOffset()[1], 2.0);
576+
EXPECT_EQ(controller_->odometry_.getBaseFrameOffset()[2], 3.0);
577+
578+
// Activate in chained mode
579+
controller_->set_chained_mode(true);
580+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
581+
ASSERT_EQ(controller_->is_in_chained_mode(), true);
582+
583+
// Setup reference interfaces for side to side motion
584+
auto side_to_side_motion = [this](double linear_y)
585+
{
586+
controller_->reference_interfaces_[0] = 0; // linear x
587+
controller_->reference_interfaces_[1] = linear_y; // linear y
588+
controller_->reference_interfaces_[2] = 0; // angular z
589+
};
590+
591+
// Setup reference interfaces for rotation
592+
auto rotation_motion = [this](double rotation_velocity)
593+
{
594+
controller_->reference_interfaces_[0] = 0; // linear x
595+
controller_->reference_interfaces_[1] = 0; // linear y
596+
controller_->reference_interfaces_[2] = rotation_velocity; // angular z
597+
};
598+
599+
const double update_rate = 50.0; // 50 Hz
600+
const double dt = 1.0 / update_rate;
601+
const double test_duration = 1.0; // 1 second test
602+
auto current_time = controller_->get_node()->now();
603+
604+
auto count = 0;
605+
for (double t = 0; t < test_duration; t += dt)
606+
{
607+
switch (count % 4)
608+
{
609+
case 0:
610+
side_to_side_motion(2.0);
611+
break;
612+
case 1:
613+
rotation_motion(-0.5);
614+
break;
615+
case 2:
616+
side_to_side_motion(-2.0);
617+
break;
618+
case 3:
619+
rotation_motion(0.5);
620+
}
621+
622+
// Call update method
623+
ASSERT_EQ(
624+
controller_->update(current_time, rclcpp::Duration::from_seconds(dt)),
625+
controller_interface::return_type::OK);
626+
627+
current_time += rclcpp::Duration::from_seconds(dt);
628+
count++;
629+
630+
// Update the state of the wheels for subsequent loop
631+
size_t fl_index = controller_->get_front_left_wheel_index();
632+
size_t fr_index = controller_->get_front_right_wheel_index();
633+
size_t rl_index = controller_->get_rear_left_wheel_index();
634+
size_t rr_index = controller_->get_rear_right_wheel_index();
635+
joint_state_values_[fl_index] = controller_->command_interfaces_[fl_index].get_value();
636+
joint_state_values_[fr_index] = controller_->command_interfaces_[fr_index].get_value();
637+
joint_state_values_[rl_index] = controller_->command_interfaces_[rl_index].get_value();
638+
joint_state_values_[rr_index] = controller_->command_interfaces_[rr_index].get_value();
639+
}
640+
641+
RCLCPP_INFO(
642+
controller_->get_node()->get_logger(), "odometry: %f, %f, %f", controller_->odometry_.getX(),
643+
controller_->odometry_.getY(), controller_->odometry_.getRz());
644+
645+
// Verify odometry remains bounded
646+
EXPECT_LT(std::abs(controller_->odometry_.getX()), 1.0);
647+
EXPECT_LT(std::abs(controller_->odometry_.getY()), 1.0);
648+
EXPECT_LT(std::abs(controller_->odometry_.getRz()), M_PI);
649+
}
650+
565651
int main(int argc, char ** argv)
566652
{
567653
::testing::InitGoogleTest(&argc, argv);

mecanum_drive_controller/test/test_mecanum_drive_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -82,6 +82,7 @@ class TestableMecanumDriveController : public mecanum_drive_controller::MecanumD
8282
FRIEND_TEST(
8383
MecanumDriveControllerTest,
8484
when_ref_timeout_zero_for_reference_callback_expect_reference_msg_being_used_only_once);
85+
FRIEND_TEST(MecanumDriveControllerTest, SideToSideAndRotationOdometryTest);
8586

8687
public:
8788
controller_interface::CallbackReturn on_configure(

0 commit comments

Comments
 (0)