Skip to content

Commit 6b5349b

Browse files
Fix shadowed class member in GenericSystem (#2561) (#2565)
(cherry picked from commit 7cbd0cc) Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 2e94a32 commit 6b5349b

File tree

3 files changed

+75
-71
lines changed

3 files changed

+75
-71
lines changed

hardware_interface/include/mock_components/generic_system.hpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -77,24 +77,24 @@ class GenericSystem : public hardware_interface::SystemInterface
7777
hardware_interface::HW_IF_ACCELERATION, hardware_interface::HW_IF_EFFORT};
7878

7979
/// The size of this vector is (standard_interfaces_.size() x nr_joints)
80-
std::vector<std::vector<double>> joint_commands_;
81-
std::vector<std::vector<double>> joint_states_;
80+
std::vector<std::vector<double>> joint_command_values_;
81+
std::vector<std::vector<double>> joint_state_values_;
8282

8383
std::vector<std::string> other_interfaces_;
8484
/// The size of this vector is (other_interfaces_.size() x nr_joints)
85-
std::vector<std::vector<double>> other_commands_;
86-
std::vector<std::vector<double>> other_states_;
85+
std::vector<std::vector<double>> other_command_values_;
86+
std::vector<std::vector<double>> other_state_values_;
8787

8888
std::vector<std::string> sensor_interfaces_;
8989
/// The size of this vector is (sensor_interfaces_.size() x nr_joints)
90-
std::vector<std::vector<double>> sensor_mock_commands_;
91-
std::vector<std::vector<double>> sensor_states_;
90+
std::vector<std::vector<double>> sensor_mock_command_values_;
91+
std::vector<std::vector<double>> sensor_state_values_;
9292

9393
std::vector<std::string> gpio_interfaces_;
9494
/// The size of this vector is (gpio_interfaces_.size() x nr_joints)
95-
std::vector<std::vector<double>> gpio_mock_commands_;
96-
std::vector<std::vector<double>> gpio_commands_;
97-
std::vector<std::vector<double>> gpio_states_;
95+
std::vector<std::vector<double>> gpio_mock_command_values_;
96+
std::vector<std::vector<double>> gpio_command_values_;
97+
std::vector<std::vector<double>> gpio_state_values_;
9898

9999
private:
100100
template <typename HandleType>

hardware_interface/src/mock_components/generic_system.cpp

Lines changed: 66 additions & 61 deletions
Original file line numberDiff line numberDiff line change
@@ -123,15 +123,15 @@ CallbackReturn GenericSystem::on_init(
123123

124124
// Initialize storage for standard interfaces
125125
initialize_storage_vectors(
126-
joint_commands_, joint_states_, standard_interfaces_, get_hardware_info().joints);
126+
joint_command_values_, joint_state_values_, standard_interfaces_, get_hardware_info().joints);
127127
// set all values without initial values to 0
128128
for (auto i = 0u; i < get_hardware_info().joints.size(); i++)
129129
{
130130
for (auto j = 0u; j < standard_interfaces_.size(); j++)
131131
{
132-
if (std::isnan(joint_states_[j][i]))
132+
if (std::isnan(joint_state_values_[j][i]))
133133
{
134-
joint_states_[j][i] = 0.0;
134+
joint_state_values_[j][i] = 0.0;
135135
}
136136
}
137137
}
@@ -148,7 +148,7 @@ CallbackReturn GenericSystem::on_init(
148148

149149
// Initialize storage for non-standard interfaces
150150
initialize_storage_vectors(
151-
other_commands_, other_states_, other_interfaces_, get_hardware_info().joints);
151+
other_command_values_, other_state_values_, other_interfaces_, get_hardware_info().joints);
152152

153153
// when following offset is used on custom interface then find its index
154154
if (!custom_interface_with_following_offset_.empty())
@@ -186,7 +186,8 @@ CallbackReturn GenericSystem::on_init(
186186
}
187187
}
188188
initialize_storage_vectors(
189-
sensor_mock_commands_, sensor_states_, sensor_interfaces_, get_hardware_info().sensors);
189+
sensor_mock_command_values_, sensor_state_values_, sensor_interfaces_,
190+
get_hardware_info().sensors);
190191

191192
// search for gpio interfaces
192193
for (const auto & gpio : get_hardware_info().gpios)
@@ -202,13 +203,13 @@ CallbackReturn GenericSystem::on_init(
202203
if (use_mock_gpio_command_interfaces_)
203204
{
204205
initialize_storage_vectors(
205-
gpio_mock_commands_, gpio_states_, gpio_interfaces_, get_hardware_info().gpios);
206+
gpio_mock_command_values_, gpio_state_values_, gpio_interfaces_, get_hardware_info().gpios);
206207
}
207208
// Real gpio command interfaces
208209
else
209210
{
210211
initialize_storage_vectors(
211-
gpio_commands_, gpio_states_, gpio_interfaces_, get_hardware_info().gpios);
212+
gpio_command_values_, gpio_state_values_, gpio_interfaces_, get_hardware_info().gpios);
212213
}
213214

214215
return CallbackReturn::SUCCESS;
@@ -226,10 +227,12 @@ std::vector<hardware_interface::StateInterface> GenericSystem::export_state_inte
226227
{
227228
// Add interface: if not in the standard list then use "other" interface list
228229
if (!get_interface(
229-
joint.name, standard_interfaces_, interface.name, i, joint_states_, state_interfaces))
230+
joint.name, standard_interfaces_, interface.name, i, joint_state_values_,
231+
state_interfaces))
230232
{
231233
if (!get_interface(
232-
joint.name, other_interfaces_, interface.name, i, other_states_, state_interfaces))
234+
joint.name, other_interfaces_, interface.name, i, other_state_values_,
235+
state_interfaces))
233236
{
234237
throw std::runtime_error(
235238
"Interface is not found in the standard nor other list. "
@@ -241,15 +244,16 @@ std::vector<hardware_interface::StateInterface> GenericSystem::export_state_inte
241244

242245
// Sensor state interfaces
243246
if (!populate_interfaces(
244-
get_hardware_info().sensors, sensor_interfaces_, sensor_states_, state_interfaces, true))
247+
get_hardware_info().sensors, sensor_interfaces_, sensor_state_values_, state_interfaces,
248+
true))
245249
{
246250
throw std::runtime_error(
247251
"Interface is not found in the standard nor other list. This should never happen!");
248252
};
249253

250254
// GPIO state interfaces
251255
if (!populate_interfaces(
252-
get_hardware_info().gpios, gpio_interfaces_, gpio_states_, state_interfaces, true))
256+
get_hardware_info().gpios, gpio_interfaces_, gpio_state_values_, state_interfaces, true))
253257
{
254258
throw std::runtime_error("Interface is not found in the gpio list. This should never happen!");
255259
}
@@ -269,11 +273,11 @@ std::vector<hardware_interface::CommandInterface> GenericSystem::export_command_
269273
{
270274
// Add interface: if not in the standard list than use "other" interface list
271275
if (!get_interface(
272-
joint.name, standard_interfaces_, interface.name, i, joint_commands_,
276+
joint.name, standard_interfaces_, interface.name, i, joint_command_values_,
273277
command_interfaces))
274278
{
275279
if (!get_interface(
276-
joint.name, other_interfaces_, interface.name, i, other_commands_,
280+
joint.name, other_interfaces_, interface.name, i, other_command_values_,
277281
command_interfaces))
278282
{
279283
throw std::runtime_error(
@@ -290,7 +294,7 @@ std::vector<hardware_interface::CommandInterface> GenericSystem::export_command_
290294
if (use_mock_sensor_command_interfaces_)
291295
{
292296
if (!populate_interfaces(
293-
get_hardware_info().sensors, sensor_interfaces_, sensor_mock_commands_,
297+
get_hardware_info().sensors, sensor_interfaces_, sensor_mock_command_values_,
294298
command_interfaces, true))
295299
{
296300
throw std::runtime_error(
@@ -302,8 +306,8 @@ std::vector<hardware_interface::CommandInterface> GenericSystem::export_command_
302306
if (use_mock_gpio_command_interfaces_)
303307
{
304308
if (!populate_interfaces(
305-
get_hardware_info().gpios, gpio_interfaces_, gpio_mock_commands_, command_interfaces,
306-
true))
309+
get_hardware_info().gpios, gpio_interfaces_, gpio_mock_command_values_,
310+
command_interfaces, true))
307311
{
308312
throw std::runtime_error(
309313
"Interface is not found in the gpio list. This should never happen!");
@@ -313,7 +317,8 @@ std::vector<hardware_interface::CommandInterface> GenericSystem::export_command_
313317
else
314318
{
315319
if (!populate_interfaces(
316-
get_hardware_info().gpios, gpio_interfaces_, gpio_commands_, command_interfaces, false))
320+
get_hardware_info().gpios, gpio_interfaces_, gpio_command_values_, command_interfaces,
321+
false))
317322
{
318323
throw std::runtime_error(
319324
"Interface is not found in the gpio list. This should never happen!");
@@ -487,7 +492,7 @@ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Dur
487492
return return_type::OK;
488493
};
489494

490-
for (size_t j = 0; j < joint_states_[POSITION_INTERFACE_INDEX].size(); ++j)
495+
for (size_t j = 0; j < joint_state_values_[POSITION_INTERFACE_INDEX].size(); ++j)
491496
{
492497
if (calculate_dynamics_)
493498
{
@@ -496,71 +501,71 @@ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Dur
496501
case ACCELERATION_INTERFACE_INDEX:
497502
{
498503
// currently we do backward integration
499-
joint_states_[POSITION_INTERFACE_INDEX][j] += // apply offset to positions only
500-
joint_states_[VELOCITY_INTERFACE_INDEX][j] * period.seconds() +
504+
joint_state_values_[POSITION_INTERFACE_INDEX][j] += // apply offset to positions only
505+
joint_state_values_[VELOCITY_INTERFACE_INDEX][j] * period.seconds() +
501506
(custom_interface_with_following_offset_.empty() ? position_state_following_offset_
502507
: 0.0);
503508

504-
joint_states_[VELOCITY_INTERFACE_INDEX][j] +=
505-
joint_states_[ACCELERATION_INTERFACE_INDEX][j] * period.seconds();
509+
joint_state_values_[VELOCITY_INTERFACE_INDEX][j] +=
510+
joint_state_values_[ACCELERATION_INTERFACE_INDEX][j] * period.seconds();
506511

507-
if (!std::isnan(joint_commands_[ACCELERATION_INTERFACE_INDEX][j]))
512+
if (!std::isnan(joint_command_values_[ACCELERATION_INTERFACE_INDEX][j]))
508513
{
509-
joint_states_[ACCELERATION_INTERFACE_INDEX][j] =
510-
joint_commands_[ACCELERATION_INTERFACE_INDEX][j];
514+
joint_state_values_[ACCELERATION_INTERFACE_INDEX][j] =
515+
joint_command_values_[ACCELERATION_INTERFACE_INDEX][j];
511516
}
512517
break;
513518
}
514519
case VELOCITY_INTERFACE_INDEX:
515520
{
516521
// currently we do backward integration
517-
joint_states_[POSITION_INTERFACE_INDEX][j] += // apply offset to positions only
518-
joint_states_[VELOCITY_INTERFACE_INDEX][j] * period.seconds() +
522+
joint_state_values_[POSITION_INTERFACE_INDEX][j] += // apply offset to positions only
523+
joint_state_values_[VELOCITY_INTERFACE_INDEX][j] * period.seconds() +
519524
(custom_interface_with_following_offset_.empty() ? position_state_following_offset_
520525
: 0.0);
521526

522-
if (!std::isnan(joint_commands_[VELOCITY_INTERFACE_INDEX][j]))
527+
if (!std::isnan(joint_command_values_[VELOCITY_INTERFACE_INDEX][j]))
523528
{
524-
const double old_velocity = joint_states_[VELOCITY_INTERFACE_INDEX][j];
529+
const double old_velocity = joint_state_values_[VELOCITY_INTERFACE_INDEX][j];
525530

526-
joint_states_[VELOCITY_INTERFACE_INDEX][j] =
527-
joint_commands_[VELOCITY_INTERFACE_INDEX][j];
531+
joint_state_values_[VELOCITY_INTERFACE_INDEX][j] =
532+
joint_command_values_[VELOCITY_INTERFACE_INDEX][j];
528533

529-
joint_states_[ACCELERATION_INTERFACE_INDEX][j] =
530-
(joint_states_[VELOCITY_INTERFACE_INDEX][j] - old_velocity) / period.seconds();
534+
joint_state_values_[ACCELERATION_INTERFACE_INDEX][j] =
535+
(joint_state_values_[VELOCITY_INTERFACE_INDEX][j] - old_velocity) / period.seconds();
531536
}
532537
break;
533538
}
534539
case POSITION_INTERFACE_INDEX:
535540
{
536-
if (!std::isnan(joint_commands_[POSITION_INTERFACE_INDEX][j]))
541+
if (!std::isnan(joint_command_values_[POSITION_INTERFACE_INDEX][j]))
537542
{
538-
const double old_position = joint_states_[POSITION_INTERFACE_INDEX][j];
539-
const double old_velocity = joint_states_[VELOCITY_INTERFACE_INDEX][j];
543+
const double old_position = joint_state_values_[POSITION_INTERFACE_INDEX][j];
544+
const double old_velocity = joint_state_values_[VELOCITY_INTERFACE_INDEX][j];
540545

541-
joint_states_[POSITION_INTERFACE_INDEX][j] = // apply offset to positions only
542-
joint_commands_[POSITION_INTERFACE_INDEX][j] +
546+
joint_state_values_[POSITION_INTERFACE_INDEX][j] = // apply offset to positions only
547+
joint_command_values_[POSITION_INTERFACE_INDEX][j] +
543548
(custom_interface_with_following_offset_.empty() ? position_state_following_offset_
544549
: 0.0);
545550

546-
joint_states_[VELOCITY_INTERFACE_INDEX][j] =
547-
(joint_states_[POSITION_INTERFACE_INDEX][j] - old_position) / period.seconds();
551+
joint_state_values_[VELOCITY_INTERFACE_INDEX][j] =
552+
(joint_state_values_[POSITION_INTERFACE_INDEX][j] - old_position) / period.seconds();
548553

549-
joint_states_[ACCELERATION_INTERFACE_INDEX][j] =
550-
(joint_states_[VELOCITY_INTERFACE_INDEX][j] - old_velocity) / period.seconds();
554+
joint_state_values_[ACCELERATION_INTERFACE_INDEX][j] =
555+
(joint_state_values_[VELOCITY_INTERFACE_INDEX][j] - old_velocity) / period.seconds();
551556
}
552557
break;
553558
}
554559
}
555560
}
556561
else
557562
{
558-
for (size_t k = 0; k < joint_states_[POSITION_INTERFACE_INDEX].size(); ++k)
563+
for (size_t k = 0; k < joint_state_values_[POSITION_INTERFACE_INDEX].size(); ++k)
559564
{
560-
if (!std::isnan(joint_commands_[POSITION_INTERFACE_INDEX][k]))
565+
if (!std::isnan(joint_command_values_[POSITION_INTERFACE_INDEX][k]))
561566
{
562-
joint_states_[POSITION_INTERFACE_INDEX][k] = // apply offset to positions only
563-
joint_commands_[POSITION_INTERFACE_INDEX][k] +
567+
joint_state_values_[POSITION_INTERFACE_INDEX][k] = // apply offset to positions only
568+
joint_command_values_[POSITION_INTERFACE_INDEX][k] +
564569
(custom_interface_with_following_offset_.empty() ? position_state_following_offset_
565570
: 0.0);
566571
}
@@ -571,53 +576,53 @@ return_type GenericSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Dur
571576
// do loopback on all other interfaces - starts from 1 or 3 because 0, 1, 3 are position,
572577
// velocity, and acceleration interface
573578
if (
574-
mirror_command_to_state(joint_states_, joint_commands_, calculate_dynamics_ ? 3 : 1) !=
575-
return_type::OK)
579+
mirror_command_to_state(
580+
joint_state_values_, joint_command_values_, calculate_dynamics_ ? 3 : 1) != return_type::OK)
576581
{
577582
return return_type::ERROR;
578583
}
579584

580585
for (const auto & mimic_joint : get_hardware_info().mimic_joints)
581586
{
582-
for (auto i = 0u; i < joint_states_.size(); ++i)
587+
for (auto i = 0u; i < joint_state_values_.size(); ++i)
583588
{
584-
joint_states_[i][mimic_joint.joint_index] =
589+
joint_state_values_[i][mimic_joint.joint_index] =
585590
mimic_joint.offset +
586-
mimic_joint.multiplier * joint_states_[i][mimic_joint.mimicked_joint_index];
591+
mimic_joint.multiplier * joint_state_values_[i][mimic_joint.mimicked_joint_index];
587592
}
588593
}
589594

590-
for (size_t i = 0; i < other_states_.size(); ++i)
595+
for (size_t i = 0; i < other_state_values_.size(); ++i)
591596
{
592-
for (size_t j = 0; j < other_states_[i].size(); ++j)
597+
for (size_t j = 0; j < other_state_values_[i].size(); ++j)
593598
{
594599
if (
595600
i == index_custom_interface_with_following_offset_ &&
596-
!std::isnan(joint_commands_[POSITION_INTERFACE_INDEX][j]))
601+
!std::isnan(joint_command_values_[POSITION_INTERFACE_INDEX][j]))
597602
{
598-
other_states_[i][j] =
599-
joint_commands_[POSITION_INTERFACE_INDEX][j] + position_state_following_offset_;
603+
other_state_values_[i][j] =
604+
joint_command_values_[POSITION_INTERFACE_INDEX][j] + position_state_following_offset_;
600605
}
601-
else if (!std::isnan(other_commands_[i][j]))
606+
else if (!std::isnan(other_command_values_[i][j]))
602607
{
603-
other_states_[i][j] = other_commands_[i][j];
608+
other_state_values_[i][j] = other_command_values_[i][j];
604609
}
605610
}
606611
}
607612

608613
if (use_mock_sensor_command_interfaces_)
609614
{
610-
mirror_command_to_state(sensor_states_, sensor_mock_commands_);
615+
mirror_command_to_state(sensor_state_values_, sensor_mock_command_values_);
611616
}
612617

613618
if (use_mock_gpio_command_interfaces_)
614619
{
615-
mirror_command_to_state(gpio_states_, gpio_mock_commands_);
620+
mirror_command_to_state(gpio_state_values_, gpio_mock_command_values_);
616621
}
617622
else
618623
{
619624
// do loopback on all gpio interfaces
620-
mirror_command_to_state(gpio_states_, gpio_commands_);
625+
mirror_command_to_state(gpio_state_values_, gpio_command_values_);
621626
}
622627

623628
return return_type::OK;

hardware_interface/test/test_component_interfaces_custom_export.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,6 @@ namespace
4242
{
4343
const auto TIME = rclcpp::Time(0);
4444
const auto PERIOD = rclcpp::Duration::from_seconds(0.01);
45-
constexpr unsigned int TRIGGER_READ_WRITE_ERROR_CALLS = 10000;
4645
} // namespace
4746

4847
using namespace ::testing; // NOLINT

0 commit comments

Comments
 (0)