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

feat: add rate parameter to component interface #57

Merged
merged 10 commits into from
Oct 19, 2023
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
3 changes: 3 additions & 0 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@
"vscode": {
"extensions": [
"ms-vscode.cpptools-extension-pack",
"ms-python.pylint",
"ms-python.autopep8",
"ms-python.isort",
"eamodio.gitlens"
]
}
Expand Down
2 changes: 1 addition & 1 deletion .vscode/c_cpp_properties.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
{
"name": "AMD",
"includePath": [
"/opt/ros/humble/include/**",
"/opt/ros/iron/include/**",
"/home/ros2/ros2_ws/install/**",
"/home/ros2/ws/install/**",
"/home/ros2/ws/src/modulo_utils/include",
Expand Down
7 changes: 7 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,11 @@
{
"C_Cpp.clang_format_style": "file:/home/ros2/.clang-format",
"cmake.sourceDirectory": "/home/ros2/ws/src/modulo_components",
"python.analysis.typeCheckingMode": "basic",
"python.languageServer": "Pylance",
"editor.rulers": [
120
],
"autopep8.args": ["--max-line-length", "120", "--experimental"],
"pylint.args": ["--generate-members", "--max-line-length", "120", "-d", "C0114", "-d", "C0115", "-d", "C0116"]
}
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,10 @@ Release Versions:
- [2.1.1](#211)
- [2.1.0](#210)

## Upcoming changes (in development)

- feat: add rate parameter to component interface (#57)

## 3.1.0

### September 27, 2023
Expand Down
2 changes: 1 addition & 1 deletion VERSION
Original file line number Diff line number Diff line change
@@ -1 +1 @@
3.1.0
3.1.1
2 changes: 1 addition & 1 deletion doxygen/doxygen.conf
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ PROJECT_NAME = "Modulo"
# could be handy for archiving the generated documentation or if some version
# control system is used.

PROJECT_NUMBER = 3.1.0
PROJECT_NUMBER = 3.1.1

# Using the PROJECT_BRIEF tag one can provide an optional one line description
# for a project that appears at the top of each page and should give viewer a
Expand Down
2 changes: 1 addition & 1 deletion source/modulo_component_interfaces/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>modulo_component_interfaces</name>
<version>3.1.0</version>
<version>3.1.1</version>
<description>Interface package for communicating with modulo components through the ROS framework</description>
<maintainer email="enrico@aica.tech">Enrico Eberhard</maintainer>
<license>GPLv3</license>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,20 @@
"registration": "modulo_components::Component",
"inherits": "",
"parameters": [
{
"display_name": "Rate",
"description": "The frequency in Hertz for all periodic callbacks",
"parameter_name": "rate",
"parameter_type": "int",
"default_value": "10"
},
{
"display_name": "Period",
"description": "The time interval in seconds for all periodic callbacks",
"description": "The time interval in seconds for all periodic callbacks. This parameter is deprecated and will be removed in the next major release. The rate parameter takes precedence and overrides the component period.",
"parameter_name": "period",
"parameter_type": "double",
"default_value": "0.1"
"default_value": "0.1",
"internal": true
}
],
"predicates": [
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,20 @@
"registration": "modulo_components::LifecycleComponent",
"inherits": "",
"parameters": [
{
"display_name": "Rate",
"description": "The frequency in Hertz for all periodic callbacks",
"parameter_name": "rate",
"parameter_type": "int",
"default_value": "10"
},
{
"display_name": "Period",
"description": "The time interval in seconds for all periodic callbacks",
"description": "The time interval in seconds for all periodic callbacks. This parameter is deprecated and will be removed in the next major release. The rate parameter takes precedence and overrides the component period.",
"parameter_name": "period",
"parameter_type": "double",
"default_value": "0.1"
"default_value": "0.1",
"internal": true
}
],
"predicates": [
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -592,14 +592,15 @@ class ComponentInterface : public NodeT {
template<class NodeT>
ComponentInterface<NodeT>::ComponentInterface(
const rclcpp::NodeOptions& options, modulo_core::communication::PublisherType publisher_type,
const std::string& fallback_name
) :
NodeT(utilities::parse_node_name(options, fallback_name), options), publisher_type_(publisher_type) {
const std::string& fallback_name)
: NodeT(utilities::parse_node_name(options, fallback_name), utilities::modify_parameter_overrides(options)),
publisher_type_(publisher_type) {
// register the parameter change callback handler
parameter_cb_handle_ = NodeT::add_on_set_parameters_callback(
[this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
return this->on_set_parameters_callback(parameters);
});
this->add_parameter("rate", 10, "The rate in Hertz for all periodic callbacks", true);
this->add_parameter("period", 0.1, "The time interval in seconds for all periodic callbacks", true);

this->predicate_publisher_ =
Expand Down Expand Up @@ -712,6 +713,13 @@ template<class NodeT>
inline bool ComponentInterface<NodeT>::validate_parameter(
const std::shared_ptr<state_representation::ParameterInterface>& parameter
) {
if (parameter->get_name() == "rate") {
auto value = parameter->get_parameter_value<int>();
if (value <= 0 || !std::isfinite(value)) {
RCLCPP_ERROR(this->get_logger(), "Value for parameter 'rate' has to be a positive finite number.");
return false;
}
}
if (parameter->get_name() == "period") {
auto value = parameter->get_parameter_value<double>();
if (value <= 0.0 || !std::isfinite(value)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,4 +61,40 @@ parse_node_name(const rclcpp::NodeOptions& options, const std::string& fallback
}
return output;
}

/**
* @brief Modify parameter overrides to handle the rate and period parameters
* @details This function checks for existence of the rate and period parameter in the parameter overrides
* and modifies them to correspond to the same value. If both the rate and the period parameter exist, the period will
* be set from the rate.
* @param options The node options passed to the component constructor
* @return The same node options with modified parameter overrides
*/
[[maybe_unused]] static rclcpp::NodeOptions modify_parameter_overrides(const rclcpp::NodeOptions& options) {
auto modified = options;
rclcpp::Parameter rate;
rclcpp::Parameter period;
std::vector<rclcpp::Parameter> parameters;
for (const auto& parameter : options.parameter_overrides()) {
if (parameter.get_name() == "rate") {
rate = parameter;
} else if (parameter.get_name() == "period") {
period = parameter;
} else {
parameters.push_back(parameter);
}
}
if (rate.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) {
period = rclcpp::Parameter("period", 1.0 / rate.as_int());
} else if (period.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) {
rate = rclcpp::Parameter("rate", static_cast<int>(1.0 / period.as_double()));
} else {
modified.parameter_overrides() = parameters;
return modified;
}
parameters.push_back(rate);
parameters.push_back(period);
modified.parameter_overrides() = parameters;
return modified;
}
}// namespace modulo_components::utilities
13 changes: 11 additions & 2 deletions source/modulo_components/modulo_components/component_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
from modulo_component_interfaces.srv import EmptyTrigger, StringTrigger
from modulo_components.exceptions import AddServiceError, AddSignalError, ComponentError, ComponentParameterError, \
LookupTransformError
from modulo_components.utilities import parse_topic_name
from modulo_components.utilities import parse_topic_name, modify_parameter_overrides
from modulo_core import EncodedState
from modulo_core.exceptions import MessageTranslationError, ParameterTranslationError
from modulo_core.translators.parameter_translators import get_ros_parameter_type, read_parameter_const, write_parameter
Expand Down Expand Up @@ -42,6 +42,8 @@ class ComponentInterface(Node):

def __init__(self, node_name: str, *args, **kwargs):
node_kwargs = {key: value for key, value in kwargs.items() if key in NODE_KWARGS}
if "parameter_overrides" in node_kwargs.keys():
node_kwargs["parameter_overrides"] = modify_parameter_overrides(node_kwargs["parameter_overrides"])
super().__init__(node_name, *args, **node_kwargs)
self._parameter_dict: Dict[str, Union[str, sr.Parameter]] = {}
self._predicates: Dict[str, Union[bool, Callable[[], bool]]] = {}
Expand All @@ -59,8 +61,10 @@ def __init__(self, node_name: str, *args, **kwargs):
self._qos = QoSProfile(depth=10)

self.add_on_set_parameters_callback(self.__on_set_parameters_callback)
self.add_parameter(sr.Parameter("rate", 10, sr.ParameterType.INT),
"The rate in Hertz for all periodic callbacks")
self.add_parameter(sr.Parameter("period", 0.1, sr.ParameterType.DOUBLE),
"Period (in s) between step function calls.")
"The time interval in seconds for all periodic callbacks")

self._predicate_publisher = self.create_publisher(Predicate, "/predicates", self._qos)
self.add_predicate("in_error_state", False)
Expand Down Expand Up @@ -200,6 +204,11 @@ def __validate_parameter(self, parameter: sr.Parameter) -> bool:
:param parameter: The parameter to be validated
:return: The validation result
"""
if parameter.get_name() == "rate":
value = parameter.get_value()
if value <= 0 or value > sys.float_info.max:
self.get_logger().error("Value for parameter 'rate' has to be a positive finite number.")
return False
if parameter.get_name() == "period":
value = parameter.get_value()
if value <= 0.0 or value > sys.float_info.max:
Expand Down
Original file line number Diff line number Diff line change
@@ -1 +1 @@
from modulo_components.utilities.utilities import parse_topic_name
from modulo_components.utilities.utilities import parse_topic_name, modify_parameter_overrides
35 changes: 35 additions & 0 deletions source/modulo_components/modulo_components/utilities/utilities.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
import re
from typing import List

from rclpy import Parameter


def parse_topic_name(topic_name: str) -> str:
Expand All @@ -12,3 +15,35 @@ def parse_topic_name(topic_name: str) -> str:
sanitized_string = re.sub("\W", "", topic_name, flags=re.ASCII).lower()
sanitized_string = sanitized_string.lstrip("_")
return sanitized_string


def modify_parameter_overrides(parameter_overrides: List[Parameter]) -> List[Parameter]:
"""
Modify parameter overrides to handle the rate and period parameters.
This function checks for existence of the rate and period parameter in the parameter overrides and modifies them to
correspond to the same value. If both the rate and the period parameter exist, the period will be set from the rate.

:param parameter_overrides: The parameter overrides passed to the component constructor
:return: The modified parameter overrides
"""
rate = Parameter("rate", type_=Parameter.Type.NOT_SET)
period = Parameter("period", type_=Parameter.Type.NOT_SET)
parameters = []
for parameter in parameter_overrides:
if parameter.name == "rate":
rate = parameter
elif parameter.name == "period":
period = parameter
else:
parameters.append(parameter)

if rate.type_ != Parameter.Type.NOT_SET:
period = Parameter("period", value=1.0 / rate.get_parameter_value().integer_value)
elif period.type_ != Parameter.Type.NOT_SET:
rate = Parameter("rate", value=int(1.0 / period.get_parameter_value().double_value))
else:
return parameters

parameters.append(rate)
parameters.append(period)
return parameters
2 changes: 1 addition & 1 deletion source/modulo_components/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>modulo_components</name>
<version>3.1.0</version>
<version>3.1.1</version>
<description>Modulo base classes that wrap ROS2 Nodes as modular components for the AICA application framework</description>
<maintainer email="baptiste@aica.tech">Baptiste Busch</maintainer>
<maintainer email="enrico@aica.tech">Enrico Eberhard</maintainer>
Expand Down
50 changes: 39 additions & 11 deletions source/modulo_components/test/cpp/test_component_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,17 @@ namespace modulo_components {

using namespace std::chrono_literals;

template<class NodeT>
std::shared_ptr<ComponentInterfacePublicInterface<NodeT>> make_component_interface(const rclcpp::NodeOptions& options) {
if (std::is_same<NodeT, rclcpp::Node>::value) {
return std::make_shared<ComponentInterfacePublicInterface<NodeT>>(
options, modulo_core::communication::PublisherType::PUBLISHER);
} else if (std::is_same<NodeT, rclcpp_lifecycle::LifecycleNode>::value) {
return std::make_shared<ComponentInterfacePublicInterface<NodeT>>(
options, modulo_core::communication::PublisherType::LIFECYCLE_PUBLISHER);
}
}

template<class NodeT>
class ComponentInterfaceTest : public ::testing::Test {
protected:
Expand All @@ -23,24 +34,41 @@ class ComponentInterfaceTest : public ::testing::Test {
}

void SetUp() override {
exec_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
if (std::is_same<NodeT, rclcpp::Node>::value) {
this->component_ = std::make_shared<ComponentInterfacePublicInterface<NodeT>>(
rclcpp::NodeOptions(), modulo_core::communication::PublisherType::PUBLISHER);
} else if (std::is_same<NodeT, rclcpp_lifecycle::LifecycleNode>::value) {
this->component_ = std::make_shared<ComponentInterfacePublicInterface<NodeT>>(
rclcpp::NodeOptions(), modulo_core::communication::PublisherType::LIFECYCLE_PUBLISHER);
}
this->exec_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
this->component_ = make_component_interface<NodeT>(rclcpp::NodeOptions());
}

std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> exec_;
std::shared_ptr<ComponentInterfacePublicInterface<NodeT>> component_;
std::shared_ptr<NodeT> node_;
};

using NodeTypes = ::testing::Types<rclcpp::Node, rclcpp_lifecycle::LifecycleNode>;
TYPED_TEST_SUITE(ComponentInterfaceTest, NodeTypes);

TYPED_TEST(ComponentInterfaceTest, RatePeriodParameters) {
std::shared_ptr<ComponentInterfacePublicInterface<TypeParam>> component;
auto node_options = rclcpp::NodeOptions();
component = make_component_interface<TypeParam>(node_options);
EXPECT_EQ(component->template get_parameter_value<int>("rate"), 10);
EXPECT_EQ(component->template get_parameter_value<double>("period"), 0.1);

node_options = rclcpp::NodeOptions().parameter_overrides({rclcpp::Parameter("rate", 200)});
component = make_component_interface<TypeParam>(node_options);
EXPECT_EQ(component->template get_parameter_value<int>("rate"), 200);
EXPECT_EQ(component->template get_parameter_value<double>("period"), 0.005);

node_options = rclcpp::NodeOptions().parameter_overrides({rclcpp::Parameter("period", 0.01)});
component = make_component_interface<TypeParam>(node_options);
EXPECT_EQ(component->template get_parameter_value<int>("rate"), 100);
EXPECT_EQ(component->template get_parameter_value<double>("period"), 0.01);

node_options =
rclcpp::NodeOptions().parameter_overrides({rclcpp::Parameter("rate", 200), rclcpp::Parameter("period", 0.01)});
component = make_component_interface<TypeParam>(node_options);
EXPECT_EQ(component->template get_parameter_value<int>("rate"), 200);
EXPECT_EQ(component->template get_parameter_value<double>("period"), 0.005);
}

TYPED_TEST(ComponentInterfaceTest, AddBoolPredicate) {
this->component_->add_predicate("foo", true);
auto predicate_iterator = this->component_->predicates_.find("foo");
Expand Down Expand Up @@ -229,9 +257,9 @@ TYPED_TEST(ComponentInterfaceTest, CreateOutput) {
EXPECT_TRUE(this->component_->periodic_outputs_.at("test"));

auto pub_interface = this->component_->outputs_.at("test");
if (typeid(this->node_) == typeid(rclcpp::Node)) {
if (std::is_same<TypeParam, rclcpp::Node>::value) {
EXPECT_EQ(pub_interface->get_type(), modulo_core::communication::PublisherType::PUBLISHER);
} else if (typeid(this->node_) == typeid(rclcpp_lifecycle::LifecycleNode)) {
} else if (std::is_same<TypeParam, rclcpp::Node>::value) {
EXPECT_EQ(pub_interface->get_type(), modulo_core::communication::PublisherType::LIFECYCLE_PUBLISHER);
}
EXPECT_EQ(pub_interface->get_message_pair()->get_type(), modulo_core::communication::MessageType::BOOL);
Expand Down
21 changes: 21 additions & 0 deletions source/modulo_components/test/python/test_component_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,27 @@ def component_interface(ros_context):
yield ComponentInterface('component_interface')


def test_rate_period_parameters(ros_context):
component_interface = ComponentInterface('component_interface')
assert component_interface.get_parameter_value("rate") == 10
assert component_interface.get_parameter_value("period") == 0.1

parameter_overrides=[rclpy.Parameter("rate", value=200)]
component_interface = ComponentInterface('component_interface', parameter_overrides=parameter_overrides)
assert component_interface.get_parameter_value("rate") == 200
assert component_interface.get_parameter_value("period") == 0.005

parameter_overrides=[rclpy.Parameter("period", value=0.01)]
component_interface = ComponentInterface('component_interface', parameter_overrides=parameter_overrides)
assert component_interface.get_parameter_value("rate") == 100
assert component_interface.get_parameter_value("period") == 0.01

parameter_overrides=[rclpy.Parameter("rate", value=200), rclpy.Parameter("period", value=0.01)]
component_interface = ComponentInterface('component_interface', parameter_overrides=parameter_overrides)
assert component_interface.get_parameter_value("rate") == 200
assert component_interface.get_parameter_value("period") == 0.005

domire8 marked this conversation as resolved.
Show resolved Hide resolved

def test_add_bool_predicate(component_interface):
component_interface.add_predicate('foo', True)
assert 'foo' in component_interface._predicates.keys()
Expand Down
2 changes: 1 addition & 1 deletion source/modulo_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>modulo_core</name>
<version>3.1.0</version>
<version>3.1.1</version>
<description>Modulo Core communication and translation utilities for interoperability with AICA Control Libraries</description>
<maintainer email="baptiste@aica.tech">Baptiste Busch</maintainer>
<maintainer email="enrico@aica.tech">Enrico Eberhard</maintainer>
Expand Down
Loading