Skip to content

Commit 2fdc1b0

Browse files
committed
Adding unit tests
Signed-off-by: CursedRock17 <[email protected]>
1 parent 654dabb commit 2fdc1b0

File tree

4 files changed

+69
-34
lines changed

4 files changed

+69
-34
lines changed

rclcpp/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,7 @@ set(${PROJECT_NAME}_SRCS
9696
src/rclcpp/node_options.cpp
9797
src/rclcpp/parameter.cpp
9898
src/rclcpp/parameter_client.cpp
99+
src/rclcpp/parameter_descriptor_wrapper.cpp
99100
src/rclcpp/parameter_event_handler.cpp
100101
src/rclcpp/parameter_events_filter.cpp
101102
src/rclcpp/parameter_map.cpp

rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
2626

2727
#include "rclcpp/node.hpp"
28+
#include "rclcpp/parameter_value.hpp"
2829
#include "node_interfaces/node_parameters_interface.hpp"
2930
#include "rclcpp/node_interfaces/get_node_parameters_interface.hpp"
3031

@@ -43,33 +44,32 @@ class ParameterDescription
4344

4445
// Builder Methods:
4546
// Describes the instances in a parameter_description object
46-
ParameterDescription & SetName(const std::string & name);
47-
ParameterDescription & SetType(std::uint8_t type);
48-
ParameterDescription & SetDescriptionText(const std::string & description);
49-
ParameterDescription & SetAdditionalConstraints(const std::string & constraints);
50-
ParameterDescription & SetReadOnly(bool read_only);
51-
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);
47+
ParameterDescription & set_name(const std::string & name);
48+
ParameterDescription & set_type(std::uint8_t type);
49+
ParameterDescription & set_description_text(const std::string & description);
50+
ParameterDescription & set_additional_constraints(const std::string & constraints);
51+
ParameterDescription & set_read_only(bool read_only);
52+
ParameterDescription & set_dynamic_typing(bool dynamic_typing);
53+
ParameterDescription & set_floating_point_description_range(float min, float max, float step);
54+
ParameterDescription & set_integer_description_range(int min, int max, int step);
5555

5656
// Need the current node in order to begin the configuration state
5757
// for it via the declare_parameter function
58-
template<typename ParameterType, typename NodeT>
59-
ParameterDescription & DeclareParameter(
60-
ParameterType default_value,
58+
template<typename NodeT>
59+
ParameterDescription & declare_parameter(
60+
const rclcpp::ParameterValue & default_value,
6161
NodeT && node)
6262
{
6363
auto node_param = rclcpp::node_interfaces::get_node_parameters_interface(node);
64-
node_param->declare_parameter<ParameterType>(
64+
node_param->declare_parameter(
6565
parameter_descriptor.name, default_value,
6666
parameter_descriptor);
6767
return *this;
6868
}
6969

7070
private:
7171
// The main descriptor object we're meant to initialize and adjust
72-
rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {};
72+
rcl_interfaces::msg::ParameterDescriptor parameter_descriptor;
7373
};
7474

7575
} // namespace rclcpp

rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp

Lines changed: 24 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ namespace rclcpp
2020
ParameterDescription::ParameterDescription()
2121
{
2222
// Need to set this in the constructor, but it doesn't necessarily need to be used
23-
parameter_descriptor.type{rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET};
23+
parameter_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET;
2424
}
2525

2626
rcl_interfaces::msg::ParameterDescriptor ParameterDescription::build() const
@@ -32,61 +32,65 @@ rcl_interfaces::msg::ParameterDescriptor ParameterDescription::build() const
3232
// Builder methods which set up the original class
3333
// They all follow the same format of initing the value given within the base class
3434
// then returning the current class
35-
ParameterDescription & ParameterDescription::SetName(const std::string & name)
35+
ParameterDescription & ParameterDescription::set_name(const std::string & name)
3636
{
3737
parameter_descriptor.name = name;
3838
return *this;
3939
}
4040

41-
ParameterDescription & ParameterDescription::SetType(std::uint8_t type)
41+
ParameterDescription & ParameterDescription::set_type(std::uint8_t type)
4242
{
4343
parameter_descriptor.type = type;
4444
return *this;
4545
}
4646

47-
ParameterDescription & ParameterDescription::SetDescriptionText(const std::string & description)
47+
ParameterDescription & ParameterDescription::set_description_text(const std::string & description)
4848
{
4949
parameter_descriptor.description = description;
5050
return *this;
5151
}
5252

53-
ParameterDescription & ParameterDescription::SetAdditionalConstraints(
53+
ParameterDescription & ParameterDescription::set_additional_constraints(
5454
const std::string & constraints)
5555
{
56-
parameter_descriptor.constraints = constraints;
56+
parameter_descriptor.additional_constraints = constraints;
5757
return *this;
5858
}
5959

60-
ParameterDescription & ParameterDescription::SetReadOnly(bool read_only)
60+
ParameterDescription & ParameterDescription::set_read_only(bool read_only)
6161
{
6262
parameter_descriptor.read_only = read_only;
6363
return *this;
6464
}
6565

66-
ParameterDescription & ParameterDescription::SetDynamicTyping(bool dynamic_typing)
66+
ParameterDescription & ParameterDescription::set_dynamic_typing(bool dynamic_typing)
6767
{
6868
parameter_descriptor.dynamic_typing = dynamic_typing;
6969
return *this;
7070
}
7171

7272
// Here is the Specific range function for this parameter description
73-
ParameterDescription & ParameterDescription::SetFloatingPointDescriptionRange(
74-
float min, float max,
75-
float step)
73+
ParameterDescription & ParameterDescription::set_floating_point_description_range(
74+
float min, float max, float step)
7675
{
77-
parameter_descriptor.floating_point_range.resize(1);
78-
parameter_descriptor.floating_point_range.at(0).from_value = min;
79-
parameter_descriptor.floating_point_range.at(0).to_value = max;
80-
parameter_descriptor.floating_point_range.at(0).step = step;
76+
if (parameter_descriptor.type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
77+
parameter_descriptor.floating_point_range.resize(1);
78+
parameter_descriptor.floating_point_range.at(0).from_value = min;
79+
parameter_descriptor.floating_point_range.at(0).to_value = max;
80+
parameter_descriptor.floating_point_range.at(0).step = step;
81+
}
8182
return *this;
8283
}
8384

84-
ParameterDescription & ParameterDescription::SetIntegerDescriptionRange(int min, int max, int step)
85+
ParameterDescription & ParameterDescription::set_integer_description_range(
86+
int min, int max, int step)
8587
{
86-
parameter_descriptor.integer_range.resize(1);
87-
parameter_descriptor.integer_range.at(0).from_value = min;
88-
parameter_descriptor.integer_range.at(0).to_value = max;
89-
parameter_descriptor.integer_range.at(0).step = step;
88+
if (parameter_descriptor.type == rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
89+
parameter_descriptor.integer_range.resize(1);
90+
parameter_descriptor.integer_range.at(0).from_value = min;
91+
parameter_descriptor.integer_range.at(0).to_value = max;
92+
parameter_descriptor.integer_range.at(0).step = step;
93+
}
9094
return *this;
9195
}
9296

rclcpp/test/rclcpp/test_parameter_service.cpp

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <vector>
2121

2222
#include "rclcpp/rclcpp.hpp"
23+
#include "rclcpp/parameter_descriptor_wrapper.hpp"
2324
#include "../../src/rclcpp/parameter_service_names.hpp"
2425

2526
using namespace std::chrono_literals;
@@ -119,3 +120,32 @@ TEST_F(TestParameterService, describe_parameters) {
119120
EXPECT_EQ(0u, parameter_descs.size());
120121
}
121122
}
123+
124+
TEST_F(TestParameterService, parameter_descriptor) {
125+
{
126+
rclcpp::ParameterDescription param_description;
127+
rclcpp::ParameterValue param_value(1);
128+
129+
param_description.set_name("int_parameter");
130+
param_description.set_type(2);
131+
param_description.set_description_text("description");
132+
param_description.set_additional_constraints("constraints");
133+
param_description.set_read_only(false);
134+
param_description.set_integer_description_range(0, 10, 1);
135+
136+
auto param = param_description.build();
137+
param_description.declare_parameter(param_value, node);
138+
139+
EXPECT_EQ("int_parameter", param.name);
140+
EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, param.type);
141+
EXPECT_EQ("description", param.description);
142+
EXPECT_EQ("constraints", param.additional_constraints);
143+
EXPECT_EQ(0u, param.read_only);
144+
EXPECT_EQ(0u, param.dynamic_typing);
145+
EXPECT_EQ(0u, param.integer_range.at(0).from_value);
146+
EXPECT_EQ(10, param.integer_range.at(0).to_value);
147+
EXPECT_EQ(1, param.integer_range.at(0).step);
148+
149+
ASSERT_EQ(1, client->get_parameter("int_parameter", 0));
150+
}
151+
}

0 commit comments

Comments
 (0)