@@ -90,18 +90,18 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init(
9090 }
9191 }
9292
93- REGISTER_DEFAULT_INTROSPECTION (" hw_start_sec" , &hw_start_sec_);
94- REGISTER_DEFAULT_INTROSPECTION (" hw_stop_sec" , &hw_stop_sec_);
95- REGISTER_DEFAULT_INTROSPECTION (" hw_slowdown" , &hw_slowdown_);
96- REGISTER_DEFAULT_INTROSPECTION (" hw_sensor_change" , &hw_sensor_change_);
93+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_start_sec" , &hw_start_sec_);
94+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_stop_sec" , &hw_stop_sec_);
95+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_slowdown" , &hw_slowdown_);
96+ REGISTER_ROS2_CONTROL_INTROSPECTION (" hw_sensor_change" , &hw_sensor_change_);
9797 for (size_t i = 0 ; i < info_.joints .size (); ++i)
9898 {
99- REGISTER_DEFAULT_INTROSPECTION (info_.joints [i].name + " .hw_state" , &hw_joint_states_[i]);
100- REGISTER_DEFAULT_INTROSPECTION (info_.joints [i].name + " .hw_command" , &hw_joint_commands_[i]);
99+ REGISTER_ROS2_CONTROL_INTROSPECTION (info_.joints [i].name + " .hw_state" , &hw_joint_states_[i]);
100+ REGISTER_ROS2_CONTROL_INTROSPECTION (info_.joints [i].name + " .hw_command" , &hw_joint_commands_[i]);
101101 }
102102 for (size_t i = 0 ; i < info_.sensors [0 ].state_interfaces .size (); ++i)
103103 {
104- REGISTER_DEFAULT_INTROSPECTION (
104+ REGISTER_ROS2_CONTROL_INTROSPECTION (
105105 info_.sensors [0 ].name + " ." + info_.sensors [0 ].state_interfaces [i].name ,
106106 &hw_sensor_states_[i]);
107107 }
0 commit comments