@@ -531,19 +531,12 @@ TEST_F(JointStateBroadcasterTest, TestCustomInterfaceMappingUpdate)
531531 state_broadcaster_->get_node ()->set_parameter (
532532 {std::string (" map_interface_to_joint_state." ) + HW_IF_POSITION, custom_interface_name_});
533533
534- // configure ok
535- ASSERT_EQ (state_broadcaster_->on_configure (rclcpp_lifecycle::State ()), NODE_SUCCESS);
536-
537- ASSERT_EQ (state_broadcaster_->on_activate (rclcpp_lifecycle::State ()), NODE_SUCCESS);
538-
539- ASSERT_EQ (
540- state_broadcaster_->update (rclcpp::Time (0 ), rclcpp::Duration::from_seconds (0.01 )),
541- controller_interface::return_type::OK);
534+ sensor_msgs::msg::JointState joint_state_msg;
535+ activate_and_get_joint_state_message (" joint_states" , joint_state_msg);
542536
543537 const size_t NUM_JOINTS = JOINT_NAMES.size ();
544538
545539 // joint state initialized
546- const auto & joint_state_msg = state_broadcaster_->realtime_joint_state_publisher_ ->msg_ ;
547540 ASSERT_THAT (joint_state_msg.name , ElementsAreArray (JOINT_NAMES));
548541 ASSERT_THAT (joint_state_msg.position , SizeIs (NUM_JOINTS));
549542 ASSERT_EQ (joint_state_msg.position [0 ], custom_joint_value_);
@@ -585,7 +578,8 @@ TEST_F(JointStateBroadcasterTest, UpdateTest)
585578 controller_interface::return_type::OK);
586579}
587580
588- void JointStateBroadcasterTest::test_published_joint_state_message (const std::string & topic)
581+ void JointStateBroadcasterTest::activate_and_get_joint_state_message (
582+ const std::string & topic, sensor_msgs::msg::JointState & joint_state_msg)
589583{
590584 auto node_state = state_broadcaster_->get_node ()->configure ();
591585 ASSERT_EQ (node_state.id (), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
@@ -616,9 +610,14 @@ void JointStateBroadcasterTest::test_published_joint_state_message(const std::st
616610 " controller/broadcaster update loop" ;
617611
618612 // take message from subscription
619- sensor_msgs::msg::JointState joint_state_msg;
620613 rclcpp::MessageInfo msg_info;
621614 ASSERT_TRUE (subscription->take (joint_state_msg, msg_info));
615+ }
616+
617+ void JointStateBroadcasterTest::test_published_joint_state_message (const std::string & topic)
618+ {
619+ sensor_msgs::msg::JointState joint_state_msg;
620+ activate_and_get_joint_state_message (topic, joint_state_msg);
622621
623622 const size_t NUM_JOINTS = joint_names_.size ();
624623 ASSERT_THAT (joint_state_msg.name , SizeIs (NUM_JOINTS));
0 commit comments