@@ -85,18 +85,18 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
8585 }
8686 }
8787
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_);
9292 for (size_t i = 0 ; i < info_.joints .size (); ++i)
9393 {
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]);
9696 }
9797 for (size_t i = 0 ; i < info_.sensors [0 ].state_interfaces .size (); ++i)
9898 {
99- REGISTER_DEFAULT_INTROSPECTION (
99+ REGISTER_ROS2_CONTROL_INTROSPECTION (
100100 info_.sensors [0 ].name + " ." + info_.sensors [0 ].state_interfaces [i].name ,
101101 &hw_sensor_states_[i]);
102102 }
0 commit comments