Skip to content

Commit 1321ae8

Browse files
Fix child_frame_id in controller_state_msg (#1601)
Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 64c00ea commit 1321ae8

File tree

3 files changed

+30
-4
lines changed

3 files changed

+30
-4
lines changed

admittance_controller/include/admittance_controller/admittance_rule_impl.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -102,8 +102,6 @@ controller_interface::return_type AdmittanceRule::reset(const size_t num_joints)
102102
state_message_.wrench_base.header.frame_id = parameters_.kinematics.base;
103103
state_message_.admittance_velocity.header.frame_id = parameters_.kinematics.base;
104104
state_message_.admittance_acceleration.header.frame_id = parameters_.kinematics.base;
105-
state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
106-
state_message_.admittance_position.child_frame_id = "admittance_offset";
107105

108106
// reset admittance state
109107
admittance_state_ = AdmittanceState(num_joints);
@@ -384,10 +382,12 @@ const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_control
384382
admittance_state_.admittance_acceleration[5];
385383

386384
state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
385+
state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
386+
state_message_.admittance_position.child_frame_id = "admittance_offset";
387387

388-
state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
389-
state_message_.ref_trans_base_ft.header.frame_id = "ft_reference";
390388
state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
389+
state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
390+
state_message_.ref_trans_base_ft.child_frame_id = parameters_.ft_sensor.frame.id;
391391

392392
Eigen::Quaterniond quat(admittance_state_.rot_base_control);
393393
state_message_.rot_base_control.w = quat.w();

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -358,6 +358,31 @@ TEST_F(AdmittanceControllerTest, receive_message_and_publish_updated_status)
358358
subscribe_and_get_messages(msg);
359359
}
360360

361+
TEST_F(AdmittanceControllerTest, check_frame_ids_in_controller_state)
362+
{
363+
SetUpController();
364+
365+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
366+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
367+
368+
broadcast_tfs(); // force torque sensor
369+
370+
ASSERT_EQ(
371+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
372+
controller_interface::return_type::OK);
373+
374+
const auto & msg = controller_->admittance_->get_controller_state();
375+
376+
// Ensure correct frame IDs
377+
ASSERT_EQ(
378+
msg.ref_trans_base_ft.header.frame_id, controller_->admittance_->parameters_.kinematics.base);
379+
ASSERT_EQ(
380+
msg.ref_trans_base_ft.child_frame_id, controller_->admittance_->parameters_.ft_sensor.frame.id);
381+
ASSERT_EQ(
382+
msg.admittance_position.header.frame_id, controller_->admittance_->parameters_.kinematics.base);
383+
ASSERT_EQ(msg.admittance_position.child_frame_id, "admittance_offset");
384+
}
385+
361386
int main(int argc, char ** argv)
362387
{
363388
::testing::InitGoogleTest(&argc, argv);

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
6767
FRIEND_TEST(AdmittanceControllerTest, check_interfaces);
6868
FRIEND_TEST(AdmittanceControllerTest, activate_success);
6969
FRIEND_TEST(AdmittanceControllerTest, receive_message_and_publish_updated_status);
70+
FRIEND_TEST(AdmittanceControllerTest, check_frame_ids_in_controller_state);
7071

7172
public:
7273
CallbackReturn on_init() override

0 commit comments

Comments
 (0)