Skip to content

Commit

Permalink
fix: move predicate publishing rate parameter to base controller
Browse files Browse the repository at this point in the history
  • Loading branch information
bpapaspyros committed Nov 29, 2024
1 parent 9324ea1 commit f3dc61b
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 11 deletions.
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": "Base controller class to combine ros2_control, control libraries and modulo" // todo: to be updated
},
"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

0 comments on commit f3dc61b

Please sign in to comment.