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: move predicate publishing rate parameter to base controller #168

Merged
merged 4 commits into from
Nov 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ Release Versions:
## Upcoming changes

- fix(components): remove incorrect log line (#166)
- fix(controllers): move predicate publishing rate parameter to BaseControllerInterface (#168)

## 5.0.2

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
{
"$schema": "https://docs.aica.tech/schemas/1-3-0/controller.schema.json",
"name": "Base Controller Interface",
"description": {
"brief": "Base controller class to combine ros2_control, control libraries and modulo"
},
"plugin": "modulo_controllers/BaseControllerInterface",
"virtual": true,
"parameters": [
{
"display_name": "Predicate publishing rate",
"description": "The rate at which to publish controller predicates (in Hertz)",
"parameter_name": "predicate_publishing_rate",
"parameter_type": "double",
"default_value": "10.0",
"internal": true
}
]
}
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,10 @@
"$schema": "https://docs.aica.tech/schemas/1-3-0/controller.schema.json",
"name": "Controller Interface",
"description": {
"brief": "Base controller class to combine ros2_control, control libraries and modulo"
"brief": "Controller interface class that includes custom parameters for derived controllers"
},
"plugin": "modulo_controllers/ControllerInterface",
"inherits": "modulo_controllers/BaseControllerInterface",
"virtual": true,
"parameters": [
{
Expand Down Expand Up @@ -48,14 +49,6 @@
"parameter_name": "input_validity_period",
"parameter_type": "double",
"default_value": "1.0"
},
{
"display_name": "Predicate publishing rate",
"description": "The rate at which to publish controller predicates (in Hertz)",
"parameter_name": "predicate_publishing_rate",
"parameter_type": "double",
"default_value": "10.0",
"internal": true
}
]
}
2 changes: 1 addition & 1 deletion source/modulo_controllers/src/BaseControllerInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn BaseCo
[this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
return this->on_set_parameters_callback(parameters);
});

add_parameter<double>("predicate_publishing_rate", 10.0, "The rate at which to publish controller predicates");
return CallbackReturn::SUCCESS;
}

Expand Down
1 change: 0 additions & 1 deletion source/modulo_controllers/src/ControllerInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Contro
"activation_timeout", 1.0, "The seconds to wait for valid data on the state interfaces before activating");
add_parameter<double>(
"input_validity_period", 1.0, "The maximum age of an input state before discarding it as expired");
add_parameter<double>("predicate_publishing_rate", 10.0, "The rate at which to publish controller predicates");

return add_interfaces();
} catch (const std::exception& e) {
Expand Down