Skip to content

Commit

Permalink
[Controller Interface] Add time and period paramters to update_refere…
Browse files Browse the repository at this point in the history
…nce_from_subscribers() (#846) #API-break

* Add Migration file for API breaking changes.

Co-authored-by: Denis Štogl <[email protected]>
  • Loading branch information
Robotgir and destogl committed Mar 28, 2023
1 parent c8cfa05 commit fea2d8a
Show file tree
Hide file tree
Showing 6 changed files with 21 additions and 5 deletions.
12 changes: 12 additions & 0 deletions MIGRATION.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Migration Notes

API changes in ros2_control releases

## ROS Rolling

#### Controller Interface

`update_reference_from_subscribers()` method got parameters and now has the following signature:
```
update_reference_from_subscribers(const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
```
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,8 @@ class ChainableControllerInterface : public ControllerInterfaceBase
*
* \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.
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ return_type ChainableControllerInterface::update(

if (!is_in_chained_mode())
{
ret = update_reference_from_subscribers();
ret = update_reference_from_subscribers(time, period);
if (ret != return_type::OK)
{
return ret;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ class TestableChainableControllerInterface
}
}

controller_interface::return_type update_reference_from_subscribers() override
controller_interface::return_type update_reference_from_subscribers(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override
{
if (reference_interface_value_ == INTERFACE_VALUE_SUBSCRIBER_ERROR)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,8 @@ TestChainableController::state_interface_configuration() const
}
}

controller_interface::return_type TestChainableController::update_reference_from_subscribers()
controller_interface::return_type TestChainableController::update_reference_from_subscribers(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
for (size_t i = 0; i < reference_interfaces_.size(); ++i)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,8 @@ class TestChainableController : public controller_interface::ChainableController
CONTROLLER_MANAGER_PUBLIC
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;

controller_interface::return_type update_reference_from_subscribers() override;
controller_interface::return_type update_reference_from_subscribers(
const rclcpp::Time & time, const rclcpp::Duration & period) override;

controller_interface::return_type update_and_write_commands(
const rclcpp::Time & time, const rclcpp::Duration & period) override;
Expand Down

0 comments on commit fea2d8a

Please sign in to comment.