@@ -85,18 +85,18 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
85
85
}
86
86
}
87
87
88
- REGISTER_DEFAULT_INTROSPECTION (" hw_start_sec" , &hw_start_sec_);
89
- REGISTER_DEFAULT_INTROSPECTION (" hw_stop_sec" , &hw_stop_sec_);
90
- REGISTER_DEFAULT_INTROSPECTION (" hw_slowdown" , &hw_slowdown_);
91
- REGISTER_DEFAULT_INTROSPECTION (" hw_sensor_change" , &hw_sensor_change_);
88
+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_start_sec" , &hw_start_sec_);
89
+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_stop_sec" , &hw_stop_sec_);
90
+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_slowdown" , &hw_slowdown_);
91
+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_sensor_change" , &hw_sensor_change_);
92
92
for (size_t i = 0 ; i < info_.joints .size (); ++i)
93
93
{
94
- REGISTER_DEFAULT_INTROSPECTION (info_.joints [i].name + " .hw_state" , &hw_joint_states_[i]);
95
- REGISTER_DEFAULT_INTROSPECTION (info_.joints [i].name + " .hw_command" , &hw_joint_commands_[i]);
94
+ REGISTER_ROS2_CONTROL_INTROSPECTION (info_.joints [i].name + " .hw_state" , &hw_joint_states_[i]);
95
+ REGISTER_ROS2_CONTROL_INTROSPECTION (info_.joints [i].name + " .hw_command" , &hw_joint_commands_[i]);
96
96
}
97
97
for (size_t i = 0 ; i < info_.sensors [0 ].state_interfaces .size (); ++i)
98
98
{
99
- REGISTER_DEFAULT_INTROSPECTION (
99
+ REGISTER_ROS2_CONTROL_INTROSPECTION (
100
100
info_.sensors [0 ].name + " ." + info_.sensors [0 ].state_interfaces [i].name ,
101
101
&hw_sensor_states_[i]);
102
102
}
0 commit comments