@@ -942,6 +942,119 @@ TEST_F(JointStateBroadcasterTest, UpdateTest)
942
942
controller_interface::return_type::OK);
943
943
}
944
944
945
+ TEST_F (JointStateBroadcasterTest, UpdatePerformanceTest)
946
+ {
947
+ const auto result = state_broadcaster_->init (
948
+ " joint_state_broadcaster" , " " , 0 , " " , state_broadcaster_->define_custom_node_options ());
949
+ ASSERT_EQ (result, controller_interface::return_type::OK);
950
+
951
+ custom_joint_value_ = 12.34 ;
952
+
953
+ // build our own test interfaces: robot has ~500 state interfaces
954
+ for (auto joint = 1u ; joint < 30 ; ++joint)
955
+ {
956
+ const auto joint_name = " joint_" + std::to_string (joint);
957
+
958
+ // standard
959
+ test_interfaces_.emplace_back (
960
+ hardware_interface::StateInterface{joint_name, " position" , &custom_joint_value_});
961
+ test_interfaces_.emplace_back (
962
+ hardware_interface::StateInterface{joint_name, " velocity" , &custom_joint_value_});
963
+ test_interfaces_.emplace_back (
964
+ hardware_interface::StateInterface{joint_name, " effort" , &custom_joint_value_});
965
+
966
+ // non standard
967
+ test_interfaces_.emplace_back (
968
+ hardware_interface::StateInterface{joint_name, " mode" , &custom_joint_value_});
969
+ test_interfaces_.emplace_back (
970
+ hardware_interface::StateInterface{joint_name, " absolute_position" , &custom_joint_value_});
971
+ test_interfaces_.emplace_back (
972
+ hardware_interface::StateInterface{joint_name, " acceleration" , &custom_joint_value_});
973
+ test_interfaces_.emplace_back (
974
+ hardware_interface::StateInterface{joint_name, " current" , &custom_joint_value_});
975
+ test_interfaces_.emplace_back (
976
+ hardware_interface::StateInterface{joint_name, " torque" , &custom_joint_value_});
977
+ test_interfaces_.emplace_back (
978
+ hardware_interface::StateInterface{joint_name, " force" , &custom_joint_value_});
979
+ test_interfaces_.emplace_back (
980
+ hardware_interface::StateInterface{joint_name, " temperature_board" , &custom_joint_value_});
981
+ test_interfaces_.emplace_back (
982
+ hardware_interface::StateInterface{joint_name, " temperature_motor" , &custom_joint_value_});
983
+
984
+ test_interfaces_.emplace_back (
985
+ hardware_interface::StateInterface{joint_name, " position.kd" , &custom_joint_value_});
986
+ test_interfaces_.emplace_back (
987
+ hardware_interface::StateInterface{joint_name, " position.ki" , &custom_joint_value_});
988
+ test_interfaces_.emplace_back (
989
+ hardware_interface::StateInterface{joint_name, " position.kp" , &custom_joint_value_});
990
+
991
+ test_interfaces_.emplace_back (
992
+ hardware_interface::StateInterface{joint_name, " velocity.kd" , &custom_joint_value_});
993
+ test_interfaces_.emplace_back (
994
+ hardware_interface::StateInterface{joint_name, " velocity.ki" , &custom_joint_value_});
995
+ test_interfaces_.emplace_back (
996
+ hardware_interface::StateInterface{joint_name, " velocity.kp" , &custom_joint_value_});
997
+
998
+ test_interfaces_.emplace_back (
999
+ hardware_interface::StateInterface{joint_name, " current.kd" , &custom_joint_value_});
1000
+ test_interfaces_.emplace_back (
1001
+ hardware_interface::StateInterface{joint_name, " current.ki" , &custom_joint_value_});
1002
+ test_interfaces_.emplace_back (
1003
+ hardware_interface::StateInterface{joint_name, " current.kp" , &custom_joint_value_});
1004
+ }
1005
+
1006
+ RCLCPP_INFO (
1007
+ state_broadcaster_->get_node ()->get_logger (), " Number of test interfaces: %lu" ,
1008
+ test_interfaces_.size ());
1009
+
1010
+ std::vector<LoanedStateInterface> state_interfaces;
1011
+ for (const auto & tif : test_interfaces_)
1012
+ {
1013
+ state_interfaces.emplace_back (tif);
1014
+ }
1015
+
1016
+ state_broadcaster_->assign_interfaces ({}, std::move (state_interfaces));
1017
+
1018
+ auto node_state = state_broadcaster_->get_node ()->configure ();
1019
+ node_state = state_broadcaster_->get_node ()->activate ();
1020
+ ASSERT_EQ (node_state.id (), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
1021
+
1022
+ if (!realtime_tools::configure_sched_fifo (50 ))
1023
+ {
1024
+ RCLCPP_WARN (
1025
+ state_broadcaster_->get_node ()->get_logger (),
1026
+ " Could not enable FIFO RT scheduling policy: with error number <%i>(%s)" , errno,
1027
+ strerror (errno));
1028
+ }
1029
+
1030
+ constexpr auto kNumSamples = 10000u ;
1031
+ std::vector<int64_t > measures;
1032
+ for (auto i = 0u ; i < kNumSamples ; ++i)
1033
+ {
1034
+ const auto now = std::chrono::steady_clock::now ();
1035
+
1036
+ ASSERT_EQ (
1037
+ state_broadcaster_->update (rclcpp::Time (0 ), rclcpp::Duration::from_seconds (0.01 )),
1038
+ controller_interface::return_type::OK);
1039
+
1040
+ // print time taken
1041
+ const auto elapsed = std::chrono::steady_clock::now () - now;
1042
+ const auto elapsed_us = std::chrono::duration_cast<std::chrono::microseconds>(elapsed);
1043
+
1044
+ measures.push_back (elapsed_us.count ());
1045
+ }
1046
+
1047
+ const auto average =
1048
+ std::accumulate (measures.begin (), measures.end (), 0.0 ) / static_cast <double >(measures.size ());
1049
+ const auto variance = std::accumulate (
1050
+ measures.begin (), measures.end (), 0.0 , [average](double accum, double x)
1051
+ { return accum + (x - average) * (x - average); }) /
1052
+ static_cast <double >(measures.size ());
1053
+
1054
+ RCLCPP_INFO (state_broadcaster_->get_node ()->get_logger (), " Average update time: %lf us" , average);
1055
+ RCLCPP_INFO (state_broadcaster_->get_node ()->get_logger (), " Variance: %lf us" , variance);
1056
+ }
1057
+
945
1058
void JointStateBroadcasterTest::activate_and_get_joint_state_message (
946
1059
const std::string & topic, sensor_msgs::msg::JointState & joint_state_msg)
947
1060
{
0 commit comments