Skip to content

Commit 364462a

Browse files
authored
[JSB] added fixes to mantain the joint names order (#1572)
1 parent d1349e1 commit 364462a

File tree

2 files changed

+70
-39
lines changed

2 files changed

+70
-39
lines changed

joint_state_broadcaster/doc/userdoc.rst

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,3 +38,25 @@ An example parameter file
3838

3939
.. generate_parameter_library_default::
4040
../src/joint_state_broadcaster_parameters.yaml
41+
42+
43+
Order of the joints in the message
44+
----------------------------------
45+
46+
The order of the joints in the message can determined by 3 different parameter settings:
47+
48+
1. No defined ``joints`` parameter and ``use_urdf_to_filter`` set to ``false``:
49+
The order of the joints in the message is the same as the order of the joints' state interfaces registered in the resource manager. This is typically the order in which the hardware components are loaded and configured.
50+
51+
2. No defined ``joints`` parameter and ``use_urdf_to_filter`` set to ``true``:
52+
The order of the joints in the message is the same as the order of the joints in the URDF file, which is inherited from the loaded URDF model and independent of the order in the `ros2_control` tag.
53+
54+
3. Defined ``joints`` parameter along with ``interfaces`` parameter:
55+
The order of the joints in the message is the same as the order of the joints in the ``joints`` parameter.
56+
57+
If the ``joints`` parameter is a subset of the total available joints in the URDF (or) the total available state interfaces, then only the joints in the ``joints`` parameter are published in the message.
58+
59+
If any of the combinations of the defined ``joints`` parameter and ``interfaces`` parameter are not in the available state interfaces, the controller will fail to activate.
60+
61+
..note::
62+
If the ``extra_joints`` parameter is set, the joints in the ``extra_joints`` parameter are appended to the end of the joint names in the message.

joint_state_broadcaster/src/joint_state_broadcaster.cpp

Lines changed: 48 additions & 39 deletions
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,17 @@ controller_interface::CallbackReturn JointStateBroadcaster::on_configure(
170170
HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_EFFORT);
171171
}
172172

173+
// joint_names reserve space for all joints
174+
const auto max_joints_size =
175+
(params_.joints.empty() ? model_.joints_.size() : params_.joints.size()) +
176+
params_.extra_joints.size();
177+
joint_names_.reserve(max_joints_size);
178+
auto & joint_state_msg = realtime_joint_state_publisher_->msg_;
179+
joint_state_msg.name.reserve(max_joints_size);
180+
joint_state_msg.position.reserve(max_joints_size);
181+
joint_state_msg.velocity.reserve(max_joints_size);
182+
joint_state_msg.effort.reserve(max_joints_size);
183+
173184
return CallbackReturn::SUCCESS;
174185
}
175186

@@ -199,23 +210,6 @@ controller_interface::CallbackReturn JointStateBroadcaster::on_deactivate(
199210
return CallbackReturn::SUCCESS;
200211
}
201212

202-
template <typename T>
203-
bool has_any_key(
204-
const std::unordered_map<std::string, T> & map, const std::vector<std::string> & keys)
205-
{
206-
bool found_key = false;
207-
for (const auto & key_item : map)
208-
{
209-
const auto & key = key_item.first;
210-
if (std::find(keys.cbegin(), keys.cend(), key) != keys.cend())
211-
{
212-
found_key = true;
213-
break;
214-
}
215-
}
216-
return found_key;
217-
}
218-
219213
bool JointStateBroadcaster::init_joint_data()
220214
{
221215
joint_names_.clear();
@@ -226,52 +220,67 @@ bool JointStateBroadcaster::init_joint_data()
226220
}
227221

228222
// loop in reverse order, this maintains the order of values at retrieval time
223+
const std::vector<std::string> joint_state_interfaces = {
224+
HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_EFFORT};
229225
for (auto si = state_interfaces_.crbegin(); si != state_interfaces_.crend(); si++)
230226
{
227+
const std::string prefix_name = si->get_prefix_name();
231228
// initialize map if name is new
232-
if (name_if_value_mapping_.count(si->get_prefix_name()) == 0)
229+
if (name_if_value_mapping_.count(prefix_name) == 0)
233230
{
234-
name_if_value_mapping_[si->get_prefix_name()] = {};
231+
name_if_value_mapping_[prefix_name] = {};
235232
}
236233
// add interface name
237234
std::string interface_name = si->get_interface_name();
238235
if (map_interface_to_joint_state_.count(interface_name) > 0)
239236
{
240237
interface_name = map_interface_to_joint_state_[interface_name];
241238
}
242-
name_if_value_mapping_[si->get_prefix_name()][interface_name] = kUninitializedValue;
243-
}
239+
name_if_value_mapping_[prefix_name][interface_name] = kUninitializedValue;
244240

245-
// filter state interfaces that have at least one of the joint_states fields,
246-
// the rest will be ignored for this message
247-
for (const auto & name_ifv : name_if_value_mapping_)
248-
{
249-
const auto & interfaces_and_values = name_ifv.second;
250-
if (has_any_key(interfaces_and_values, {HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_EFFORT}))
241+
// filter state interfaces that have at least one of the joint_states fields,
242+
// the rest will be ignored for this message
243+
if (
244+
std::find(joint_state_interfaces.begin(), joint_state_interfaces.end(), interface_name) !=
245+
joint_state_interfaces.end())
251246
{
252247
if (
253248
!params_.use_urdf_to_filter || !params_.joints.empty() || !is_model_loaded_ ||
254-
model_.getJoint(name_ifv.first))
249+
model_.getJoint(prefix_name))
255250
{
256-
joint_names_.push_back(name_ifv.first);
251+
if (std::find(joint_names_.begin(), joint_names_.end(), prefix_name) == joint_names_.end())
252+
{
253+
joint_names_.push_back(prefix_name);
254+
}
257255
}
258256
}
259257
}
258+
std::reverse(joint_names_.begin(), joint_names_.end());
259+
if (is_model_loaded_ && params_.use_urdf_to_filter && params_.joints.empty())
260+
{
261+
std::vector<std::string> joint_names_filtered;
262+
for (const auto & [joint_name, urdf_joint] : model_.joints_)
263+
{
264+
if (urdf_joint && urdf_joint->type != urdf::Joint::FIXED)
265+
{
266+
if (std::find(joint_names_.begin(), joint_names_.end(), joint_name) != joint_names_.end())
267+
{
268+
joint_names_filtered.push_back(joint_name);
269+
}
270+
}
271+
}
272+
joint_names_ = joint_names_filtered;
273+
}
260274

261275
// Add extra joints from parameters, each joint will be added to joint_names_ and
262276
// name_if_value_mapping_ if it is not already there
263-
rclcpp::Parameter extra_joints;
264-
if (get_node()->get_parameter("extra_joints", extra_joints))
277+
for (const auto & extra_joint_name : params_.extra_joints)
265278
{
266-
const std::vector<std::string> & extra_joints_names = extra_joints.as_string_array();
267-
for (const auto & extra_joint_name : extra_joints_names)
279+
if (name_if_value_mapping_.count(extra_joint_name) == 0)
268280
{
269-
if (name_if_value_mapping_.count(extra_joint_name) == 0)
270-
{
271-
name_if_value_mapping_[extra_joint_name] = {
272-
{HW_IF_POSITION, 0.0}, {HW_IF_VELOCITY, 0.0}, {HW_IF_EFFORT, 0.0}};
273-
joint_names_.push_back(extra_joint_name);
274-
}
281+
name_if_value_mapping_[extra_joint_name] = {
282+
{HW_IF_POSITION, 0.0}, {HW_IF_VELOCITY, 0.0}, {HW_IF_EFFORT, 0.0}};
283+
joint_names_.push_back(extra_joint_name);
275284
}
276285
}
277286

0 commit comments

Comments
 (0)