|
14 | 14 | namespace rclcpp |
15 | 15 | { |
16 | 16 |
|
17 | | -// Implements ParameterDesription class with builder design pattern |
| 17 | +// Implments ParameterDesription class with builder design pattern |
18 | 18 | class ParameterDescription |
19 | 19 | { |
20 | 20 | public: |
21 | | - ParameterDescription(const std::string& name, std::uint8_t type, std::string description, std::string additional_constraints, bool read_only. bool dynamic_typing) : m_name{name}, parameter_descriptor.type{type}, m_description{description}, m_additional_constraints{additional_constraints}, read_only{read_only}, dyanmic_typing{m_dyanmic_typing}{}; |
22 | 21 | // List of classes the builder manages |
23 | | - ParameterDescription(); |
| 22 | + class FloatingPointDescription; |
24 | 23 |
|
| 24 | + // Two constructors in case certain methods don't need to declare_parameters with a Type T in the form of a template |
| 25 | + ParameterDescription(std::string name, std::uint8_t type, std::string description, std::string additional_constraints, bool read_only. bool dynamic_typing) : m_name{name}, parameter_descriptor.type{type}, m_description{description}, m_additional_constraints{additional_constraints}, read_only{read_only}, dyanmic_typing{m_dyanmic_typing}{}; |
| 26 | + |
| 27 | +private: |
| 28 | + // The main descriptor object we're meant to adjust |
| 29 | + rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {}; |
| 30 | + |
| 31 | + // Copies all the information in ParameterDescriptor.msg - https://github.com/ros2/rcl_interfaces/blob/rolling/rcl_interfaces/msg/ParameterDescriptor.msg |
| 32 | + std::string m_name; |
| 33 | + std::string m_description; |
| 34 | + |
| 35 | + // Parameter Constraints |
| 36 | + std::string m_additional_constraints; |
| 37 | + bool m_read_only; |
| 38 | + bool m_dynamic_typing; |
| 39 | + |
| 40 | +}; |
| 41 | + |
| 42 | +class ParameterDescription::FloatingPointDescription |
| 43 | +{ |
| 44 | +public: |
25 | 45 | // Our Main build methods which will construct the base class |
26 | 46 | ParameterDescription build() const; |
27 | 47 |
|
28 | | - //Builder Methods - Describes the instances in a parameter_descriptionobject |
29 | | - ParameterDescription& SetName(const std::string& name); |
30 | | - ParameterDescription& SetType(std::uint8_t type); |
31 | | - ParameterDescription& SetDescriptionText(const std::string& description); |
32 | | - ParameterDescription& SetAdditionalConstraints(const std::string& constraints); |
33 | | - ParameterDescription& SetReadOnly(bool read_only); |
34 | | - ParameterDescription& SetDynamicTyping(bool dynamic_typing); |
| 48 | + //Builder Method - Mains |
| 49 | + FloatingPointDescription& SetName(std::string name); |
| 50 | + FloatingPointDescription& SetType(std::uint8_t type); |
| 51 | + FloatingPointDescription& SetDescription(std::string description); |
| 52 | + FloatingPointDescription& SetAdditionalConstraints(std::string constraints); |
| 53 | + FloatingPointDescription& SetReadOnly(bool read_only); |
| 54 | + FloatingPointDescription& SetDynamicTyping(bool dynamic_typing); |
35 | 55 |
|
36 | 56 | // Need the current node in order to begin the configuraiton state forit via the declare_parameter function which setups up the Node |
37 | 57 | template<typename ParameterType> |
38 | | - ParameterDescription& DeclareParameter<ParameterType>(ParameterType default_value, std::unique_ptr<rclcpp::Node> required_node) |
| 58 | + FloatingPointDescription& DeclareParameter<ParameterType>(ParameterType default_value, std::shared_ptr<rclcpp::Node> required_node) |
39 | 59 | { |
40 | 60 | required_node->declare_parameter<ParameterType>(m_name, default_value, parameter_descriptor); |
41 | 61 | return *this; |
42 | 62 | } |
| 63 | + // Extended build methods specific to this class |
| 64 | + FloatingPointDescription& SetMin(float min); |
| 65 | + FloatingPointDescription& SetMax(float max); |
| 66 | + FloatingPointDescription& SetStep(float step); |
43 | 67 |
|
44 | | - // Simplification Methods - The user should be able to set up ranges easily, they should then be able to call a function which sets up the specifics for this class (The floating point range for parameter description) |
| 68 | + // Simplification Method - Outside of the base clss that the user should be able to set up easily, they should then be able to call a function which setups up the specifics for this class (The floating point parameter description) |
45 | 69 | // Here we will have a difference between generic types and templated types |
46 | | - // Also we can use default values for min, max, and float. The other option is to utilize SetMin methods and similar and check if we have a range, if not, then we should resize one |
47 | | - ParameterDescription& SetFloatingPointDescriptionRange(float min = 0.0f, float max = 1.0f, float step = 0.0f); |
| 70 | + FloatingPointDescription& SetFloatingPointDescription(float min, float max, float step); |
48 | 71 | // We will again need access to the current development node to declare its parameters |
49 | 72 | template<typename ParameterType> |
50 | | - ParameterDescription& SetFloatingPointDescriptionRange(std::unique_ptr<rclcpp::Node> currentNode, const std::string& name, ParameterType default_value, float min = 0.0f, float max = 1.0f, float step = 0.0f) |
| 73 | + FloatingPointDescription& SetFloatingPointDescription(std::string name, ParameterType default_value, float min, float max, float step) |
51 | 74 | { |
52 | 75 | parameter_descriptor.floating_point_range.resize(1); |
53 | 76 | parameter_descriptor.floating_point_range.at(0).from_value = min; |
54 | 77 | parameter_descriptor.floating_point_range.at(0).to_value = max; |
55 | 78 | parameter_descriptor.floating_point_range.at(0).step = step; |
56 | 79 |
|
57 | | - // For this version of the function we can outright declare the parameters using the specified type |
58 | | - currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor); |
59 | | - |
60 | 80 | return *this; |
61 | 81 | } |
62 | 82 |
|
63 | | - ParameterDescription& SetIntegerPointDescriptionRange(int min = 0, int max = 1, int step = 0); |
64 | | - // We will again need access to the current development node to declare its parameters |
65 | | - template<typename ParameterType> |
66 | | - ParameterDescription& SetIntegerPointDescriptionRange(std::unique_ptr<rclcpp::Node> currentNode, const std::string& name, ParameterType default_value, int min = 0, int max = 1, int step = 0) |
67 | | - { |
68 | | - parameter_descriptor.integer_range.resize(1); |
69 | | - parameter_descriptor.integer_range.at(0).from_value = min; |
70 | | - parameter_descriptor.integer_range.at(0).to_value = max; |
71 | | - parameter_descriptor.integer_range.at(0).step = step; |
72 | | - |
73 | | - // For this version of the function we can outright declare the parameters using the specified type |
74 | | - currentNode->declare_parameter<ParameterType>(name, default_value, parameter_descriptor); |
75 | | - |
76 | | - return *this; |
77 | | - } |
78 | | - |
79 | | - // Extended build methods specific to the ranges, but with overloaded versions |
80 | | - ParameterDescription& SetMin(float min); |
81 | | - ParameterDescription& SetMax(float max); |
82 | | - ParameterDescription& SetStep(float step); |
83 | | - |
84 | | - ParameterDescription& SetMin(int min); |
85 | | - ParameterDescription& SetMax(int max); |
86 | | - ParameterDescription& SetStep(int step); |
87 | 83 |
|
88 | 84 | private: |
89 | | - // The main descriptor object we're meant to initialize and adjust |
90 | 85 | rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {}; |
91 | | - |
92 | | - // Copies all the information in ParameterDescriptor.msg - https://github.com/ros2/rcl_interfaces/blob/rolling/rcl_interfaces/msg/ParameterDescriptor.msg |
93 | | - std::string m_name; |
94 | | - std::string m_description; |
| 86 | + std::string m_name{""}; |
95 | 87 | parameter_descriptor.type{rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET}; |
| 88 | + std::string m_description{""}; |
96 | 89 |
|
97 | | - // Parameter Constraints |
98 | | - std::string m_additional_constraints; |
99 | | - bool m_read_only; |
100 | | - bool m_dynamic_typing; |
| 90 | + std::string m_additional_constraints{""}; |
| 91 | + bool m_read_only{false}; |
| 92 | + bool m_dynamic_typing{false}; |
101 | 93 |
|
102 | 94 | // This is a floating point so we'll use floating points in the range |
103 | | - float m_min_float {0.0f}; |
104 | | - float m_max_float {1.0f}; |
105 | | - float m_step_float {0.0f}; |
106 | | - |
107 | | - // Now here is the integer version so we'll use ints in the range |
108 | | - int m_min_int {0}; |
109 | | - int m_max_int {1}; |
110 | | - int m_step_int {0}; |
| 95 | + float m_min{0.0f}; |
| 96 | + float m_max{1.0f}; |
| 97 | + float m_step{0.0f}; |
111 | 98 | }; |
112 | 99 |
|
113 | 100 | } // namespace rclcpp |
|
0 commit comments