diff --git a/example_12/controllers/src/passthrough_controller.cpp b/example_12/controllers/src/passthrough_controller.cpp index 92660438a..345bf9b6f 100644 --- a/example_12/controllers/src/passthrough_controller.cpp +++ b/example_12/controllers/src/passthrough_controller.cpp @@ -85,6 +85,11 @@ controller_interface::CallbackReturn PassthroughController::on_configure( reference_interfaces_.resize( reference_interface_names_.size(), std::numeric_limits::quiet_NaN()); + for (size_t i = 0; i < reference_interface_names_.size(); i++) + { + REGISTER_ROS2_CONTROL_INTROSPECTION(reference_interface_names_[i], &reference_interfaces_[i]); + } + return controller_interface::CallbackReturn::SUCCESS; } diff --git a/example_12/hardware/rrbot.cpp b/example_12/hardware/rrbot.cpp index a6cc4cf77..cba7968bd 100644 --- a/example_12/hardware/rrbot.cpp +++ b/example_12/hardware/rrbot.cpp @@ -81,6 +81,10 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init( } } + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_); + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_); + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_); + return hardware_interface::CallbackReturn::SUCCESS; } diff --git a/example_4/hardware/rrbot_system_with_sensor.cpp b/example_4/hardware/rrbot_system_with_sensor.cpp index f211bb970..928ceb9a2 100644 --- a/example_4/hardware/rrbot_system_with_sensor.cpp +++ b/example_4/hardware/rrbot_system_with_sensor.cpp @@ -85,6 +85,11 @@ hardware_interface::CallbackReturn RRBotSystemWithSensorHardware::on_init( } } + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_start_sec", &hw_start_sec_); + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_stop_sec", &hw_stop_sec_); + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_slowdown", &hw_slowdown_); + REGISTER_ROS2_CONTROL_INTROSPECTION("hw_sensor_change", &hw_sensor_change_); + return hardware_interface::CallbackReturn::SUCCESS; }