Skip to content

Commit 4aa06d7

Browse files
mergify[bot]rehanshah17christophfroehlich
authored
Fix child_frame_id in controller_state_msg (backport #1601) (#1834)
Co-authored-by: Rehan Shah <85085446+rehanshah17@users.noreply.github.com> Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
1 parent b0569b2 commit 4aa06d7

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
@@ -99,8 +99,6 @@ controller_interface::return_type AdmittanceRule::reset(const size_t num_joints)
9999
state_message_.wrench_base.header.frame_id = parameters_.kinematics.base;
100100
state_message_.admittance_velocity.header.frame_id = parameters_.kinematics.base;
101101
state_message_.admittance_acceleration.header.frame_id = parameters_.kinematics.base;
102-
state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
103-
state_message_.admittance_position.child_frame_id = "admittance_offset";
104102

105103
// reset admittance state
106104
admittance_state_ = AdmittanceState(num_joints);
@@ -389,10 +387,12 @@ const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_control
389387
admittance_state_.admittance_acceleration[5];
390388

391389
state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
390+
state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
391+
state_message_.admittance_position.child_frame_id = "admittance_offset";
392392

393-
state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
394-
state_message_.ref_trans_base_ft.header.frame_id = "ft_reference";
395393
state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
394+
state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
395+
state_message_.ref_trans_base_ft.child_frame_id = parameters_.ft_sensor.frame.id;
396396

397397
Eigen::Quaterniond quat(admittance_state_.rot_base_control);
398398
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
@@ -339,6 +339,31 @@ TEST_F(AdmittanceControllerTest, receive_message_and_publish_updated_status)
339339
subscribe_and_get_messages(msg);
340340
}
341341

342+
TEST_F(AdmittanceControllerTest, check_frame_ids_in_controller_state)
343+
{
344+
SetUpController();
345+
346+
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
347+
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
348+
349+
broadcast_tfs(); // force torque sensor
350+
351+
ASSERT_EQ(
352+
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
353+
controller_interface::return_type::OK);
354+
355+
const auto & msg = controller_->admittance_->get_controller_state();
356+
357+
// Ensure correct frame IDs
358+
ASSERT_EQ(
359+
msg.ref_trans_base_ft.header.frame_id, controller_->admittance_->parameters_.kinematics.base);
360+
ASSERT_EQ(
361+
msg.ref_trans_base_ft.child_frame_id, controller_->admittance_->parameters_.ft_sensor.frame.id);
362+
ASSERT_EQ(
363+
msg.admittance_position.header.frame_id, controller_->admittance_->parameters_.kinematics.base);
364+
ASSERT_EQ(msg.admittance_position.child_frame_id, "admittance_offset");
365+
}
366+
342367
int main(int argc, char ** argv)
343368
{
344369
::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
@@ -68,6 +68,7 @@ class TestableAdmittanceController : public admittance_controller::AdmittanceCon
6868
FRIEND_TEST(AdmittanceControllerTest, check_interfaces);
6969
FRIEND_TEST(AdmittanceControllerTest, activate_success);
7070
FRIEND_TEST(AdmittanceControllerTest, receive_message_and_publish_updated_status);
71+
FRIEND_TEST(AdmittanceControllerTest, check_frame_ids_in_controller_state);
7172

7273
public:
7374
CallbackReturn on_init() override

0 commit comments

Comments
 (0)