@@ -50,108 +50,115 @@ class ParameterDescription
5050
5151 // Builder Methods:
5252 // Describes the instances in a parameter_description object
53- ParameterDescription& SetName (const std::string& name);
54- ParameterDescription& SetType (std::uint8_t type);
55- ParameterDescription& SetDescriptionText (const std::string& description);
56- ParameterDescription& SetAdditionalConstraints (const std::string& constraints);
57- ParameterDescription& SetReadOnly (bool read_only);
58- ParameterDescription& SetDynamicTyping (bool dynamic_typing);
53+ ParameterDescription & SetName (const std::string & name);
54+ ParameterDescription & SetType (std::uint8_t type);
55+ ParameterDescription & SetDescriptionText (const std::string & description);
56+ ParameterDescription & SetAdditionalConstraints (const std::string & constraints);
57+ ParameterDescription & SetReadOnly (bool read_only);
58+ ParameterDescription & SetDynamicTyping (bool dynamic_typing);
5959
6060 // Need the current node in order to begin the configuration state
6161 // for it via the declare_parameter function which setups the Node
6262 template <typename ParameterType>
63- ParameterDescription&
63+ ParameterDescription &
6464 DeclareParameter (ParameterType default_value, rclcpp::Node::SharedPtr required_node_ptr)
65- {
66- required_node_ptr->declare_parameter <ParameterType>(parameter_descriptor.name , default_value, parameter_descriptor);
67- return *this ;
68- }
65+ {
66+ required_node_ptr->declare_parameter <ParameterType>(
67+ parameter_descriptor.name , default_value,
68+ parameter_descriptor);
69+ return *this ;
70+ }
6971
7072 template <typename ParameterType>
71- ParameterDescription& DeclareParameter
72- (ParameterType default_value,
73- rclcpp_lifecycle::LifecycleNode::SharedPtr required_node_ptr)
74- {
75- required_node_ptr->declare_parameter <ParameterType>
76- (parameter_descriptor.name , default_value, parameter_descriptor);
77- return *this ;
78- }
73+ ParameterDescription & DeclareParameter (
74+ ParameterType default_value,
75+ rclcpp_lifecycle::LifecycleNode::SharedPtr required_node_ptr)
76+ {
77+ required_node_ptr->declare_parameter <ParameterType>
78+ (parameter_descriptor.name , default_value,
79+ parameter_descriptor);
80+ return *this ;
81+ }
7982
8083 // Simplification Methods:
8184 // The user should be able to set up ranges easily, they should then be able to call a function
8285 // this function sets up the specifics for this class
8386 // Here we will have a difference between generic types and templated types
84- ParameterDescription& SetFloatingPointDescriptionRange
85- (float min = 0 .0f , float max = 1 .0f , float step = 0 .0f );
87+ ParameterDescription & SetFloatingPointDescriptionRange (
88+ float min = 0 .0f , float max = 1 .0f ,
89+ float step = 0 .0f );
8690 // We will again need access to the current development node to declare its parameters
8791 template <typename ParameterType>
88- ParameterDescription& SetFloatingPointDescriptionRange
89- ( rclcpp::Node::SharedPtr currentNode, const std::string& name,
90- ParameterType default_value, float min = 0 .0f ,
91- float max = 1 .0f , float step = 0 .0f )
92- {
93- parameter_descriptor.floating_point_range .resize (1 );
94- parameter_descriptor.floating_point_range .at (0 ).from_value = min;
95- parameter_descriptor.floating_point_range .at (0 ).to_value = max;
96- parameter_descriptor.floating_point_range .at (0 ).step = step;
97-
98- // For this function we can outright declare the parameters using the specified type
99- currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
100-
101- return *this ;
102- }
92+ ParameterDescription & SetFloatingPointDescriptionRange (
93+ rclcpp::Node::SharedPtr currentNode, const std::string & name,
94+ ParameterType default_value, float min = 0 .0f ,
95+ float max = 1 .0f , float step = 0 .0f )
96+ {
97+ parameter_descriptor.floating_point_range .resize (1 );
98+ parameter_descriptor.floating_point_range .at (0 ).from_value = min;
99+ parameter_descriptor.floating_point_range .at (0 ).to_value = max;
100+ parameter_descriptor.floating_point_range .at (0 ).step = step;
101+
102+ // For this function we can outright declare the parameters using the specified type
103+ currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
104+
105+ return *this ;
106+ }
103107
104108 template <typename ParameterType>
105- ParameterDescription& SetFloatingPointDescriptionRange
106- (rclcpp_lifecycle::LifecycleNode::SharedPtr currentNode,
107- const std::string& name, ParameterType default_value,
108- float min = 0 .0f , float max = 1 .0f , float step = 0 .0f )
109- {
110- parameter_descriptor.floating_point_range .resize (1 );
111- parameter_descriptor.floating_point_range .at (0 ).from_value = min;
112- parameter_descriptor.floating_point_range .at (0 ).to_value = max;
113- parameter_descriptor.floating_point_range .at (0 ).step = step;
114-
115- // For this function we can outright declare the parameters using the specified type
116- currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
117-
118- return *this ;
119- }
120-
121- ParameterDescription& SetIntegerDescriptionRange (int min = 0 , int max = 1 , int step = 0 );
109+ ParameterDescription & SetFloatingPointDescriptionRange (
110+ rclcpp_lifecycle::LifecycleNode::SharedPtr currentNode,
111+ const std::string & name, ParameterType default_value,
112+ float min = 0 .0f , float max = 1 .0f ,
113+ float step = 0 .0f )
114+ {
115+ parameter_descriptor.floating_point_range .resize (1 );
116+ parameter_descriptor.floating_point_range .at (0 ).from_value = min;
117+ parameter_descriptor.floating_point_range .at (0 ).to_value = max;
118+ parameter_descriptor.floating_point_range .at (0 ).step = step;
119+
120+ // For this function we can outright declare the parameters using the specified type
121+ currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
122+
123+ return *this ;
124+ }
125+
126+ ParameterDescription & SetIntegerDescriptionRange (int min = 0 , int max = 1 , int step = 0 );
122127 // We will again need access to the current development node to declare its parameters
123128 template <typename ParameterType>
124- ParameterDescription& SetIntegerDescriptionRange
125- (rclcpp::Node::SharedPtr currentNode, const std::string& name,
126- ParameterType default_value, int min = 0 , int max = 1 , int step = 0 )
127- {
128- parameter_descriptor.integer_range .resize (1 );
129- parameter_descriptor.integer_range .at (0 ).from_value = min;
130- parameter_descriptor.integer_range .at (0 ).to_value = max;
131- parameter_descriptor.integer_range .at (0 ).step = step;
132-
133- // For this version of the function we can outright declare the parameters using the specified type
134- currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
135-
136- return *this ;
137- }
129+ ParameterDescription & SetIntegerDescriptionRange (
130+ rclcpp::Node::SharedPtr currentNode, const std::string & name,
131+ ParameterType default_value, int min = 0 ,
132+ int max = 1 , int step = 0 )
133+ {
134+ parameter_descriptor.integer_range .resize (1 );
135+ parameter_descriptor.integer_range .at (0 ).from_value = min;
136+ parameter_descriptor.integer_range .at (0 ).to_value = max;
137+ parameter_descriptor.integer_range .at (0 ).step = step;
138+
139+ // For this function we can outright declare the parameters using the specified type
140+ currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
141+
142+ return *this ;
143+ }
138144
139145 // We will again need access to the current development node to declare its parameters
140146 template <typename ParameterType>
141- ParameterDescription& SetIntegerDescriptionRange
142- (rclcpp_lifecycle::LifecycleNode currentNode, const std::string& name,
143- ParameterType default_value, int min = 0 , int max = 1 , int step = 0 )
144- {
145- parameter_descriptor.integer_range .resize (1 );
146- parameter_descriptor.integer_range .at (0 ).from_value = min;
147- parameter_descriptor.integer_range .at (0 ).to_value = max;
148- parameter_descriptor.integer_range .at (0 ).step = step;
149-
150- // For this function we can outright declare the parameters using the specified type
151- currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
152-
153- return *this ;
154- }
147+ ParameterDescription & SetIntegerDescriptionRange (
148+ rclcpp_lifecycle::LifecycleNode currentNode, const std::string & name,
149+ ParameterType default_value, int min = 0 ,
150+ int max = 1 , int step = 0 )
151+ {
152+ parameter_descriptor.integer_range .resize (1 );
153+ parameter_descriptor.integer_range .at (0 ).from_value = min;
154+ parameter_descriptor.integer_range .at (0 ).to_value = max;
155+ parameter_descriptor.integer_range .at (0 ).step = step;
156+
157+ // For this function we can outright declare the parameters using the specified type
158+ currentNode->declare_parameter <ParameterType>(name, default_value, parameter_descriptor);
159+
160+ return *this ;
161+ }
155162private:
156163 // The main descriptor object we're meant to initialize and adjust
157164 rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {};
0 commit comments