Skip to content

Commit 654dabb

Browse files
committed
Use node interfaces for more variance
Signed-off-by: CursedRock17 <[email protected]>
1 parent d0d97a4 commit 654dabb

File tree

2 files changed

+12
-110
lines changed

2 files changed

+12
-110
lines changed

rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp

Lines changed: 10 additions & 104 deletions
Original file line numberDiff line numberDiff line change
@@ -22,18 +22,11 @@
2222
#include <string>
2323

2424
// Additional ROS libraries needed
25-
#include "rcl_interfaces/msg/list_parameters_result.hpp"
2625
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
27-
#include "rcl_interfaces/msg/set_parameters_result.hpp"
2826

29-
#include "rclcpp/callback_group.hpp"
30-
#include "rclcpp/context.hpp"
31-
#include "macros.hpp"
3227
#include "rclcpp/node.hpp"
33-
#include "node_interfaces/node_base_interface.hpp"
34-
#include "node_interfaces/node_base.hpp"
35-
#include "rcl_interfaces/srv/list_parameters.hpp"
36-
#include "rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp"
28+
#include "node_interfaces/node_parameters_interface.hpp"
29+
#include "rclcpp/node_interfaces/get_node_parameters_interface.hpp"
3730

3831
namespace rclcpp
3932
{
@@ -56,111 +49,24 @@ class ParameterDescription
5649
ParameterDescription & SetAdditionalConstraints(const std::string & constraints);
5750
ParameterDescription & SetReadOnly(bool read_only);
5851
ParameterDescription & SetDynamicTyping(bool dynamic_typing);
52+
ParameterDescription & SetFloatingPointDescriptionRange(float min = 0.0f, float max = 1.0f,
53+
float step = 0.0f);
54+
ParameterDescription & SetIntegerDescriptionRange(int min = 0, int max = 1, int step = 0);
5955

6056
// Need the current node in order to begin the configuration state
61-
// for it via the declare_parameter function which setups the Node
62-
template<typename ParameterType>
63-
ParameterDescription & DeclareParameter(
64-
ParameterType default_value,
65-
rclcpp::Node::SharedPtr required_node_ptr)
66-
{
67-
required_node_ptr->declare_parameter<ParameterType>(
68-
parameter_descriptor.name, default_value,
69-
parameter_descriptor);
70-
return *this;
71-
}
72-
73-
template<typename ParameterType>
57+
// for it via the declare_parameter function
58+
template<typename ParameterType, typename NodeT>
7459
ParameterDescription & DeclareParameter(
7560
ParameterType default_value,
76-
rclcpp_lifecycle::LifecycleNode::SharedPtr required_node_ptr)
61+
NodeT && node)
7762
{
78-
required_node_ptr->declare_parameter<ParameterType>(
63+
auto node_param = rclcpp::node_interfaces::get_node_parameters_interface(node);
64+
node_param->declare_parameter<ParameterType>(
7965
parameter_descriptor.name, default_value,
8066
parameter_descriptor);
8167
return *this;
8268
}
8369

84-
// Simplification Methods:
85-
// The user should be able to set up ranges easily, they should then be able to call a function
86-
// this function sets up the specifics for this class
87-
// Here we will have a difference between generic types and templated types
88-
ParameterDescription & SetFloatingPointDescriptionRange(
89-
float min = 0.0f, float max = 1.0f,
90-
float step = 0.0f);
91-
// We will again need access to the current development node to declare its parameters
92-
template<typename ParameterType>
93-
ParameterDescription & SetFloatingPointDescriptionRange(
94-
rclcpp::Node::SharedPtr currentNode, const std::string & name,
95-
ParameterType default_value, float min = 0.0f,
96-
float max = 1.0f, float step = 0.0f)
97-
{
98-
parameter_descriptor.floating_point_range.resize(1);
99-
parameter_descriptor.floating_point_range.at(0).from_value = min;
100-
parameter_descriptor.floating_point_range.at(0).to_value = max;
101-
parameter_descriptor.floating_point_range.at(0).step = step;
102-
103-
// For this function we can outright declare the parameters using the specified type
104-
currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor);
105-
106-
return *this;
107-
}
108-
109-
template<typename ParameterType>
110-
ParameterDescription & SetFloatingPointDescriptionRange(
111-
rclcpp_lifecycle::LifecycleNode::SharedPtr currentNode,
112-
const std::string & name, ParameterType default_value,
113-
float min = 0.0f, float max = 1.0f,
114-
float step = 0.0f)
115-
{
116-
parameter_descriptor.floating_point_range.resize(1);
117-
parameter_descriptor.floating_point_range.at(0).from_value = min;
118-
parameter_descriptor.floating_point_range.at(0).to_value = max;
119-
parameter_descriptor.floating_point_range.at(0).step = step;
120-
121-
// For this function we can outright declare the parameters using the specified type
122-
currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor);
123-
124-
return *this;
125-
}
126-
127-
ParameterDescription & SetIntegerDescriptionRange(int min = 0, int max = 1, int step = 0);
128-
// We will again need access to the current development node to declare its parameters
129-
template<typename ParameterType>
130-
ParameterDescription & SetIntegerDescriptionRange(
131-
rclcpp::Node::SharedPtr currentNode, const std::string & name,
132-
ParameterType default_value, int min = 0,
133-
int max = 1, int step = 0)
134-
{
135-
parameter_descriptor.integer_range.resize(1);
136-
parameter_descriptor.integer_range.at(0).from_value = min;
137-
parameter_descriptor.integer_range.at(0).to_value = max;
138-
parameter_descriptor.integer_range.at(0).step = step;
139-
140-
// For this function we can outright declare the parameters using the specified type
141-
currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor);
142-
143-
return *this;
144-
}
145-
146-
// We will again need access to the current development node to declare its parameters
147-
template<typename ParameterType>
148-
ParameterDescription & SetIntegerDescriptionRange(
149-
rclcpp_lifecycle::LifecycleNode currentNode, const std::string & name,
150-
ParameterType default_value, int min = 0,
151-
int max = 1, int step = 0)
152-
{
153-
parameter_descriptor.integer_range.resize(1);
154-
parameter_descriptor.integer_range.at(0).from_value = min;
155-
parameter_descriptor.integer_range.at(0).to_value = max;
156-
parameter_descriptor.integer_range.at(0).step = step;
157-
158-
// For this function we can outright declare the parameters using the specified type
159-
currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor);
160-
161-
return *this;
162-
}
163-
16470
private:
16571
// The main descriptor object we're meant to initialize and adjust
16672
rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {};

rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp

Lines changed: 2 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,4 @@
11
// Copyright 2023 Open Source Robotics Foundation, Inc.
2-
// v
32
//
43
// Licensed under the Apache License, Version 2.0 (the "License");
54
// you may not use this file except in compliance with the License.
@@ -13,20 +12,17 @@
1312
// See the License for the specific language governing permissions and
1413
// limitations under the License.
1514

16-
#include "../../include/rclcpp/parameter_descriptor_wrapper.hpp"
15+
#include "rclcpp/parameter_descriptor_wrapper.hpp"
1716

1817
namespace rclcpp
1918
{
2019

2120
ParameterDescription::ParameterDescription()
2221
{
23-
// Copies all the information in ParameterDescriptor.message
24-
// Need to set this in the constructor, but it doesn't necessarily need to be used
22+
// Need to set this in the constructor, but it doesn't necessarily need to be used
2523
parameter_descriptor.type{rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET};
2624
}
2725

28-
// ParameterDescription - ParameterDescription
29-
// First the build methods to connect to the base class in the builder
3026
rcl_interfaces::msg::ParameterDescriptor ParameterDescription::build() const
3127
{
3228
// Return some some sort message

0 commit comments

Comments
 (0)