Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix API break coming from ChainableControllerInterface @ Iron #44

Draft
wants to merge 2 commits into
base: jazzy-devel
Choose a base branch
from

Conversation

ArthurVal
Copy link
Collaborator

Inside the ros2_control repo, since Iron (branch iron), and therefore Jazzy (tag 4.16.0), the ChainableControllerInterface interface changes its definition:

-  virtual return_type update_reference_from_subscribers() = 0;
+  virtual return_type update_reference_from_subscribers(
+    const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

Complete diff output from ros_control chainable_controller_interface.hpp repo:

$ git diff humble...4.16.0 -- controller_interface/include/controller_interface/chainable_controller_interface.hpp
diff --git a/controller_interface/include/controller_interface/chainable_controller_interface.hpp b/controller_interface/include/controller_interface/chainable_controller_interface.hpp
index 5008a1b5..2e39f038 100644
--- a/controller_interface/include/controller_interface/chainable_controller_interface.hpp
+++ b/controller_interface/include/controller_interface/chainable_controller_interface.hpp
@@ -15,6 +15,7 @@
 #ifndef CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_
 #define CONTROLLER_INTERFACE__CHAINABLE_CONTROLLER_INTERFACE_HPP_

+#include <string>
 #include <vector>

 #include "controller_interface/controller_interface_base.hpp"
@@ -41,7 +42,8 @@ public:
   virtual ~ChainableControllerInterface() = default;

   /**
-   * Control step update. Command interfaces are updated based on on reference inputs and current states.
+   * Control step update. Command interfaces are updated based on on reference inputs and current
+   * states.
    * **The method called in the (real-time) control loop.**
    *
    * \param[in] time The time at the start of this control loop iteration
@@ -54,6 +56,9 @@ public:
   CONTROLLER_INTERFACE_PUBLIC
   bool is_chainable() const final;

+  CONTROLLER_INTERFACE_PUBLIC
+  std::vector<hardware_interface::StateInterface> export_state_interfaces() final;
+
   CONTROLLER_INTERFACE_PUBLIC
   std::vector<hardware_interface::CommandInterface> export_reference_interfaces() final;

@@ -64,8 +69,19 @@ public:
   bool is_in_chained_mode() const final;

 protected:
-  /// Virtual method that each chainable controller should implement to export its chainable
-  /// interfaces.
+  /// Virtual method that each chainable controller should implement to export its read-only
+  /// chainable interfaces.
+  /**
+   * Each chainable controller implements this methods where all its state(read only) interfaces are
+   * exported. The method has the same meaning as `export_state_interfaces` method from
+   * hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.
+   *
+   * \returns list of StateInterfaces that other controller can use as their inputs.
+   */
+  virtual std::vector<hardware_interface::StateInterface> on_export_state_interfaces();
+
+  /// Virtual method that each chainable controller should implement to export its read/write
+  /// chainable interfaces.
   /**
    * Each chainable controller implements this methods where all input (command) interfaces are
    * exported. The method has the same meaning as `export_command_interface` method from
@@ -73,7 +89,7 @@ protected:
    *
    * \returns list of CommandInterfaces that other controller can use as their outputs.
    */
-  virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() = 0;
+  virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces();

   /// Virtual method that each chainable controller should implement to switch chained mode.
   /**
@@ -83,7 +99,9 @@ protected:
    *
    * \param[in] flag marking a switch to or from chained mode.
    *
-   * \returns true if controller successfully switched between "chained" and "external" mode. \default returns true so the method don't have to be overridden if controller can always switch chained mode.
+   * \returns true if controller successfully switched between "chained" and "external" mode.
+   * \default returns true so the method don't have to be overridden if controller can always switch
+   * chained mode.
    */
   virtual bool on_set_chained_mode(bool chained_mode);

@@ -94,7 +112,8 @@ protected:
    *
    * \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
    */
-  virtual return_type update_reference_from_subscribers() = 0;
+  virtual return_type update_reference_from_subscribers(
+    const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

   /// Execute calculations of the controller and update command interfaces.
   /**
@@ -110,7 +129,12 @@ protected:
   virtual return_type update_and_write_commands(
     const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

+  /// Storage of values for state interfaces
+  std::vector<std::string> exported_state_interface_names_;
+  std::vector<double> state_interfaces_values_;
+
   /// Storage of values for reference interfaces
+  std::vector<std::string> exported_reference_interface_names_;
   std::vector<double> reference_interfaces_;

 private:

@ArthurVal ArthurVal added the bug Something isn't working label Dec 11, 2024
@ArthurVal
Copy link
Collaborator Author

I highly recommend to not merge this until the humble-devel stuffs are sorted out.
After the humble branch is clean we will be able to rebase the jazzy-devel into humble-devel and merge this afterwards.

@MaximilienNaveau
Copy link
Collaborator

Actually there another major change I would like to do with these changes.
In practice the reference_interface implemented in humble are nothing but states coming from a state_estimator.
In the case of a fixed robot, I implemented a dummy joint_state_estimator that simply forward the state of the joints.
Ideally we would modify the joint_state_estimator to export the state_interfaces (optionally filtered).
And we would only use the state_interfaces with a prefix inside the linear_feedback_controller to either use the raw state or the one from another state_estimator.

What do you think?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants