Skip to content

Commit 47b18bc

Browse files
committed
fixed the copy and paste ros-controls#504 issue, added the test check_frame_ids_in_controller_state
1 parent ac35696 commit 47b18bc

File tree

2 files changed

+21
-1
lines changed

2 files changed

+21
-1
lines changed

admittance_controller/include/admittance_controller/admittance_rule_impl.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -394,7 +394,7 @@ const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_control
394394
state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
395395

396396
state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
397-
state_message_.ref_trans_base_ft.header.frame_id = "ft_reference";
397+
state_message_.ref_trans_base_ft.child_frame = parameters_.ft_sensor.frame.id;
398398
state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
399399

400400
Eigen::Quaterniond quat(admittance_state_.rot_base_control);

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -313,6 +313,26 @@ TEST_F(AdmittanceControllerTest, publish_status_success)
313313
// }
314314
}
315315

316+
TEST_F(AdmittanceControllerTest, check_frame_ids_in_controller_state)
317+
{
318+
SetUpController();
319+
320+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
321+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
322+
323+
broadcast_tfs(); // force torque sensor
324+
325+
ASSERT_EQ(
326+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
327+
controller_interface::return_type::OK);
328+
329+
const auto& msg = controller_->admittance_->get_controller_state();
330+
331+
// Ensure correct frame IDs
332+
ASSERT_EQ(msg.ref_trans_base_ft.header.frame_id, controller_->admittance_->parameters_.kinematics.base);
333+
ASSERT_EQ(msg.ref_trans_base_ft.child_frame, controller_->admittance_->parameters_.ft_sensor.frame.id);
334+
}
335+
316336
TEST_F(AdmittanceControllerTest, receive_message_and_publish_updated_status)
317337
{
318338
SetUpController();

0 commit comments

Comments
 (0)