Skip to content

Commit 39c8ad3

Browse files
Fix joint_state_broadcaster performance issues (#1640)
1 parent 0a20c8f commit 39c8ad3

File tree

4 files changed

+204
-27
lines changed

4 files changed

+204
-27
lines changed

joint_state_broadcaster/include/joint_state_broadcaster/joint_state_broadcaster.hpp

+19
Original file line numberDiff line numberDiff line change
@@ -86,6 +86,7 @@ class JointStateBroadcaster : public controller_interface::ControllerInterface
8686

8787
protected:
8888
bool init_joint_data();
89+
void init_auxiliary_data();
8990
void init_joint_state_msg();
9091
void init_dynamic_joint_state_msg();
9192
bool use_all_available_interfaces() const;
@@ -113,6 +114,24 @@ class JointStateBroadcaster : public controller_interface::ControllerInterface
113114

114115
urdf::Model model_;
115116
bool is_model_loaded_ = false;
117+
118+
std::vector<double *> mapped_values_;
119+
120+
struct JointStateData
121+
{
122+
JointStateData(const double & position, const double & velocity, const double & effort)
123+
: position_(position), velocity_(velocity), effort_(effort)
124+
{
125+
}
126+
127+
const double & position_;
128+
const double & velocity_;
129+
const double & effort_;
130+
};
131+
132+
std::vector<JointStateData> joint_states_data_;
133+
134+
std::vector<std::vector<const double *>> dynamic_joint_states_data_;
116135
};
117136

118137
} // namespace joint_state_broadcaster

joint_state_broadcaster/src/joint_state_broadcaster.cpp

+70-27
Original file line numberDiff line numberDiff line change
@@ -195,6 +195,7 @@ controller_interface::CallbackReturn JointStateBroadcaster::on_activate(
195195
return CallbackReturn::ERROR;
196196
}
197197

198+
init_auxiliary_data();
198199
init_joint_state_msg();
199200
init_dynamic_joint_state_msg();
200201

@@ -287,6 +288,22 @@ bool JointStateBroadcaster::init_joint_data()
287288
return true;
288289
}
289290

291+
void JointStateBroadcaster::init_auxiliary_data()
292+
{
293+
// save the mapping of state interfaces to joint states
294+
mapped_values_.clear();
295+
for (auto i = 0u; i < state_interfaces_.size(); ++i)
296+
{
297+
std::string interface_name = state_interfaces_[i].get_interface_name();
298+
if (map_interface_to_joint_state_.count(interface_name) > 0)
299+
{
300+
interface_name = map_interface_to_joint_state_[interface_name];
301+
}
302+
mapped_values_.push_back(
303+
&name_if_value_mapping_[state_interfaces_[i].get_prefix_name()][interface_name]);
304+
}
305+
}
306+
290307
void JointStateBroadcaster::init_joint_state_msg()
291308
{
292309
const size_t num_joints = joint_names_.size();
@@ -300,6 +317,30 @@ void JointStateBroadcaster::init_joint_state_msg()
300317
joint_state_msg.position.resize(num_joints, kUninitializedValue);
301318
joint_state_msg.velocity.resize(num_joints, kUninitializedValue);
302319
joint_state_msg.effort.resize(num_joints, kUninitializedValue);
320+
321+
// save joint state data
322+
auto get_address =
323+
[&](const std::string & joint_name, const std::string & interface_name) -> const double &
324+
{
325+
const auto & interfaces_and_values = name_if_value_mapping_.at(joint_name);
326+
const auto interface_and_value = interfaces_and_values.find(interface_name);
327+
if (interface_and_value != interfaces_and_values.cend())
328+
{
329+
return interface_and_value->second;
330+
}
331+
else
332+
{
333+
return kUninitializedValue;
334+
}
335+
};
336+
337+
joint_states_data_.clear();
338+
for (auto i = 0u; i < joint_names_.size(); ++i)
339+
{
340+
joint_states_data_.push_back(JointStateData(
341+
get_address(joint_names_[i], HW_IF_POSITION), get_address(joint_names_[i], HW_IF_VELOCITY),
342+
get_address(joint_names_[i], HW_IF_EFFORT)));
343+
}
303344
}
304345

305346
void JointStateBroadcaster::init_dynamic_joint_state_msg()
@@ -320,6 +361,22 @@ void JointStateBroadcaster::init_dynamic_joint_state_msg()
320361
}
321362
dynamic_joint_state_msg.interface_values.emplace_back(if_value);
322363
}
364+
365+
// save dynamic joint state data
366+
dynamic_joint_states_data_.clear();
367+
const auto & msg = realtime_dynamic_joint_state_publisher_->msg_;
368+
for (auto ji = 0u; ji < msg.joint_names.size(); ++ji)
369+
{
370+
dynamic_joint_states_data_.push_back(std::vector<const double *>());
371+
372+
const auto & name = msg.joint_names[ji];
373+
374+
for (auto ii = 0u; ii < msg.interface_values[ji].interface_names.size(); ++ii)
375+
{
376+
const auto & interface_name = msg.interface_values[ji].interface_names[ii];
377+
dynamic_joint_states_data_[ji].push_back(&name_if_value_mapping_[name][interface_name]);
378+
}
379+
}
323380
}
324381

325382
bool JointStateBroadcaster::use_all_available_interfaces() const
@@ -346,18 +403,14 @@ double get_value(
346403
controller_interface::return_type JointStateBroadcaster::update(
347404
const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
348405
{
349-
for (const auto & state_interface : state_interfaces_)
406+
for (auto i = 0u; i < state_interfaces_.size(); ++i)
350407
{
351-
std::string interface_name = state_interface.get_interface_name();
352-
if (map_interface_to_joint_state_.count(interface_name) > 0)
408+
// no retries, just try to get the latest value once
409+
const auto & opt = state_interfaces_[i].get_optional(0);
410+
if (opt.has_value())
353411
{
354-
interface_name = map_interface_to_joint_state_[interface_name];
412+
*mapped_values_[i] = opt.value();
355413
}
356-
name_if_value_mapping_[state_interface.get_prefix_name()][interface_name] =
357-
state_interface.get_value();
358-
RCLCPP_DEBUG(
359-
get_node()->get_logger(), "%s: %f\n", state_interface.get_name().c_str(),
360-
state_interface.get_value());
361414
}
362415

363416
if (realtime_joint_state_publisher_ && realtime_joint_state_publisher_->trylock())
@@ -369,32 +422,22 @@ controller_interface::return_type JointStateBroadcaster::update(
369422
// update joint state message and dynamic joint state message
370423
for (size_t i = 0; i < joint_names_.size(); ++i)
371424
{
372-
joint_state_msg.position[i] =
373-
get_value(name_if_value_mapping_, joint_names_[i], HW_IF_POSITION);
374-
joint_state_msg.velocity[i] =
375-
get_value(name_if_value_mapping_, joint_names_[i], HW_IF_VELOCITY);
376-
joint_state_msg.effort[i] = get_value(name_if_value_mapping_, joint_names_[i], HW_IF_EFFORT);
425+
joint_state_msg.position[i] = joint_states_data_[i].position_;
426+
joint_state_msg.velocity[i] = joint_states_data_[i].velocity_;
427+
joint_state_msg.effort[i] = joint_states_data_[i].effort_;
377428
}
378429
realtime_joint_state_publisher_->unlockAndPublish();
379430
}
380431

381432
if (realtime_dynamic_joint_state_publisher_ && realtime_dynamic_joint_state_publisher_->trylock())
382433
{
383-
auto & dynamic_joint_state_msg = realtime_dynamic_joint_state_publisher_->msg_;
384-
dynamic_joint_state_msg.header.stamp = time;
385-
for (size_t joint_index = 0; joint_index < dynamic_joint_state_msg.joint_names.size();
386-
++joint_index)
434+
auto & msg = realtime_dynamic_joint_state_publisher_->msg_;
435+
msg.header.stamp = time;
436+
for (auto ji = 0u; ji < msg.joint_names.size(); ++ji)
387437
{
388-
const auto & name = dynamic_joint_state_msg.joint_names[joint_index];
389-
for (size_t interface_index = 0;
390-
interface_index <
391-
dynamic_joint_state_msg.interface_values[joint_index].interface_names.size();
392-
++interface_index)
438+
for (auto ii = 0u; ii < msg.interface_values[ji].interface_names.size(); ++ii)
393439
{
394-
const auto & interface_name =
395-
dynamic_joint_state_msg.interface_values[joint_index].interface_names[interface_index];
396-
dynamic_joint_state_msg.interface_values[joint_index].values[interface_index] =
397-
name_if_value_mapping_[name][interface_name];
440+
msg.interface_values[ji].values[ii] = *dynamic_joint_states_data_[ji][ii];
398441
}
399442
}
400443
realtime_dynamic_joint_state_publisher_->unlockAndPublish();

joint_state_broadcaster/test/test_joint_state_broadcaster.cpp

+113
Original file line numberDiff line numberDiff line change
@@ -942,6 +942,119 @@ TEST_F(JointStateBroadcasterTest, UpdateTest)
942942
controller_interface::return_type::OK);
943943
}
944944

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+
9451058
void JointStateBroadcasterTest::activate_and_get_joint_state_message(
9461059
const std::string & topic, sensor_msgs::msg::JointState & joint_state_msg)
9471060
{

joint_state_broadcaster/test/test_joint_state_broadcaster.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,8 @@ class JointStateBroadcasterTest : public ::testing::Test
109109
hardware_interface::StateInterface joint_X_custom_state{
110110
joint_names_[0], custom_interface_name_, &custom_joint_value_};
111111

112+
std::vector<hardware_interface::StateInterface> test_interfaces_;
113+
112114
std::unique_ptr<FriendJointStateBroadcaster> state_broadcaster_;
113115
};
114116

0 commit comments

Comments
 (0)