Rename parameter options (#745)
* rename initial_parameters in NodeOptions to parameter_overrides Signed-off-by: William Woodall <william@osrfoundation.org> * rename automatically_declare_initial_parameters to automatically_declare_parameters_from_overrides Signed-off-by: William Woodall <william@osrfoundation.org> * some additional renames I missed Signed-off-by: William Woodall <william@osrfoundation.org> * add test for setting after declaring with parameter overrides Signed-off-by: William Woodall <william@osrfoundation.org> * fixup NodeOptions docs Signed-off-by: William Woodall <william+github@osrfoundation.org> Co-Authored-By: chapulina <louise@openrobotics.org> * clarify relationship between allow_undeclared_parameters and parameter_overrides Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
d2b2f9124e
commit
ecc95009f1
9 changed files with 86 additions and 58 deletions
|
@ -63,13 +63,13 @@ public:
|
|||
const node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||
const node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||
const node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||
const std::vector<Parameter> & initial_parameters,
|
||||
const std::vector<Parameter> & parameter_overrides,
|
||||
bool start_parameter_services,
|
||||
bool start_parameter_event_publisher,
|
||||
const rclcpp::QoS & parameter_event_qos,
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
|
||||
bool allow_undeclared_parameters,
|
||||
bool automatically_declare_initial_parameters);
|
||||
bool automatically_declare_parameters_from_overrides);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
|
@ -143,7 +143,7 @@ public:
|
|||
|
||||
RCLCPP_PUBLIC
|
||||
const std::map<std::string, rclcpp::ParameterValue> &
|
||||
get_initial_parameter_values() const override;
|
||||
get_parameter_overrides() const override;
|
||||
|
||||
private:
|
||||
RCLCPP_DISABLE_COPY(NodeParameters)
|
||||
|
@ -154,7 +154,7 @@ private:
|
|||
|
||||
std::map<std::string, ParameterInfo> parameters_;
|
||||
|
||||
std::map<std::string, rclcpp::ParameterValue> initial_parameter_values_;
|
||||
std::map<std::string, rclcpp::ParameterValue> parameter_overrides_;
|
||||
|
||||
bool allow_undeclared_ = false;
|
||||
|
||||
|
|
|
@ -183,7 +183,7 @@ public:
|
|||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
const std::map<std::string, rclcpp::ParameterValue> &
|
||||
get_initial_parameter_values() const = 0;
|
||||
get_parameter_overrides() const = 0;
|
||||
};
|
||||
|
||||
} // namespace node_interfaces
|
||||
|
|
|
@ -40,7 +40,7 @@ public:
|
|||
*
|
||||
* - context = rclcpp::contexts::default_context::get_global_default_context()
|
||||
* - arguments = {}
|
||||
* - initial_parameters = {}
|
||||
* - parameter_overrides = {}
|
||||
* - use_global_arguments = true
|
||||
* - use_intra_process_comms = false
|
||||
* - start_parameter_services = true
|
||||
|
@ -49,7 +49,7 @@ public:
|
|||
* - with history setting and depth from rmw_qos_profile_parameter_events
|
||||
* - parameter_event_publisher_options = rclcpp::PublisherOptionsBase
|
||||
* - allow_undeclared_parameters = false
|
||||
* - automatically_declare_initial_parameters = false
|
||||
* - automatically_declare_parameters_from_overrides = false
|
||||
* - allocator = rcl_get_default_allocator()
|
||||
*
|
||||
* \param[in] allocator allocator to use in construction of NodeOptions.
|
||||
|
@ -107,31 +107,31 @@ public:
|
|||
NodeOptions &
|
||||
arguments(const std::vector<std::string> & arguments);
|
||||
|
||||
/// Return a reference to the list of initial parameters.
|
||||
/// Return a reference to the list of parameter overrides.
|
||||
RCLCPP_PUBLIC
|
||||
std::vector<rclcpp::Parameter> &
|
||||
initial_parameters();
|
||||
parameter_overrides();
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
const std::vector<rclcpp::Parameter> &
|
||||
initial_parameters() const;
|
||||
parameter_overrides() const;
|
||||
|
||||
/// Set the initial parameters, return this for parameter idiom.
|
||||
/// Set the parameters overrides, return this for parameter idiom.
|
||||
/**
|
||||
* These initial parameter values are used to change the initial value
|
||||
* These parameter overrides are used to change the initial value
|
||||
* of declared parameters within the node, overriding hard coded default
|
||||
* values if necessary.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
NodeOptions &
|
||||
initial_parameters(const std::vector<rclcpp::Parameter> & initial_parameters);
|
||||
parameter_overrides(const std::vector<rclcpp::Parameter> & parameter_overrides);
|
||||
|
||||
/// Append a single initial parameter, parameter idiom style.
|
||||
/// Append a single parameter override, parameter idiom style.
|
||||
template<typename ParameterT>
|
||||
NodeOptions &
|
||||
append_initial_parameter(const std::string & name, const ParameterT & value)
|
||||
append_parameter_override(const std::string & name, const ParameterT & value)
|
||||
{
|
||||
this->initial_parameters().emplace_back(name, rclcpp::ParameterValue(value));
|
||||
this->parameter_overrides().emplace_back(name, rclcpp::ParameterValue(value));
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
@ -247,29 +247,35 @@ public:
|
|||
* If true, allow any parameter name to be set on the node without first
|
||||
* being declared.
|
||||
* Otherwise, setting an undeclared parameter will raise an exception.
|
||||
*
|
||||
* This option being true does not affect parameter_overrides, as the first
|
||||
* set action will implicitly declare the parameter and therefore consider
|
||||
* any parameter overrides.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
NodeOptions &
|
||||
allow_undeclared_parameters(bool allow_undeclared_parameters);
|
||||
|
||||
/// Return the automatically_declare_initial_parameters flag.
|
||||
/// Return the automatically_declare_parameters_from_overrides flag.
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
automatically_declare_initial_parameters() const;
|
||||
automatically_declare_parameters_from_overrides() const;
|
||||
|
||||
/// Set the automatically_declare_initial_parameters, return this.
|
||||
/// Set the automatically_declare_parameters_from_overrides, return this.
|
||||
/**
|
||||
* If true, automatically iterate through the node's initial parameters and
|
||||
* If true, automatically iterate through the node's parameter overrides and
|
||||
* implicitly declare any that have not already been declared.
|
||||
* Otherwise, parameters passed to the node's initial_parameters, and/or the
|
||||
* global initial parameter values, which are not explicitly declared will
|
||||
* not appear on the node at all.
|
||||
* Otherwise, parameters passed to the node's parameter_overrides, and/or the
|
||||
* global arguments (e.g. parameter overrides from a YAML file), which are
|
||||
* not explicitly declared will not appear on the node at all, even if
|
||||
* `allow_undeclared_parameters` is true.
|
||||
* Already declared parameters will not be re-declared, and parameters
|
||||
* declared in this way will use the default constructed ParameterDescriptor.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
NodeOptions &
|
||||
automatically_declare_initial_parameters(bool automatically_declare_initial_parameters);
|
||||
automatically_declare_parameters_from_overrides(
|
||||
bool automatically_declare_parameters_from_overrides);
|
||||
|
||||
/// Return the rcl_allocator_t to be used.
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -302,7 +308,7 @@ private:
|
|||
|
||||
std::vector<std::string> arguments_ {};
|
||||
|
||||
std::vector<rclcpp::Parameter> initial_parameters_ {};
|
||||
std::vector<rclcpp::Parameter> parameter_overrides_ {};
|
||||
|
||||
bool use_global_arguments_ {true};
|
||||
|
||||
|
@ -320,7 +326,7 @@ private:
|
|||
|
||||
bool allow_undeclared_parameters_ {false};
|
||||
|
||||
bool automatically_declare_initial_parameters_ {false};
|
||||
bool automatically_declare_parameters_from_overrides_ {false};
|
||||
|
||||
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
|
||||
};
|
||||
|
|
|
@ -132,13 +132,13 @@ Node::Node(
|
|||
node_topics_,
|
||||
node_services_,
|
||||
node_clock_,
|
||||
options.initial_parameters(),
|
||||
options.parameter_overrides(),
|
||||
options.start_parameter_services(),
|
||||
options.start_parameter_event_publisher(),
|
||||
options.parameter_event_qos(),
|
||||
options.parameter_event_publisher_options(),
|
||||
options.allow_undeclared_parameters(),
|
||||
options.automatically_declare_initial_parameters()
|
||||
options.automatically_declare_parameters_from_overrides()
|
||||
)),
|
||||
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
|
||||
node_base_,
|
||||
|
|
|
@ -51,13 +51,13 @@ NodeParameters::NodeParameters(
|
|||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||
const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||
const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
||||
const std::vector<rclcpp::Parameter> & parameter_overrides,
|
||||
bool start_parameter_services,
|
||||
bool start_parameter_event_publisher,
|
||||
const rclcpp::QoS & parameter_event_qos,
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
|
||||
bool allow_undeclared_parameters,
|
||||
bool automatically_declare_initial_parameters)
|
||||
bool automatically_declare_parameters_from_overrides)
|
||||
: allow_undeclared_(allow_undeclared_parameters),
|
||||
events_publisher_(nullptr),
|
||||
node_logging_(node_logging),
|
||||
|
@ -151,21 +151,21 @@ NodeParameters::NodeParameters(
|
|||
|
||||
// Combine parameter yaml files, overwriting values in older ones
|
||||
for (auto & param : iter->second) {
|
||||
initial_parameter_values_[param.get_name()] =
|
||||
parameter_overrides_[param.get_name()] =
|
||||
rclcpp::ParameterValue(param.get_value_message());
|
||||
}
|
||||
}
|
||||
|
||||
// initial values passed to constructor overwrite yaml file sources
|
||||
for (auto & param : initial_parameters) {
|
||||
initial_parameter_values_[param.get_name()] =
|
||||
// parameter overrides passed to constructor will overwrite overrides from yaml file sources
|
||||
for (auto & param : parameter_overrides) {
|
||||
parameter_overrides_[param.get_name()] =
|
||||
rclcpp::ParameterValue(param.get_value_message());
|
||||
}
|
||||
|
||||
// If asked, initialize any parameters that ended up in the initial parameter values,
|
||||
// but did not get declared explcitily by this point.
|
||||
if (automatically_declare_initial_parameters) {
|
||||
for (const auto & pair : this->get_initial_parameter_values()) {
|
||||
if (automatically_declare_parameters_from_overrides) {
|
||||
for (const auto & pair : this->get_parameter_overrides()) {
|
||||
if (!this->has_parameter(pair.first)) {
|
||||
this->declare_parameter(
|
||||
pair.first,
|
||||
|
@ -389,7 +389,7 @@ NodeParameters::declare_parameter(
|
|||
default_value,
|
||||
parameter_descriptor,
|
||||
parameters_,
|
||||
initial_parameter_values_,
|
||||
parameter_overrides_,
|
||||
on_parameters_set_callback_,
|
||||
¶meter_event);
|
||||
|
||||
|
@ -520,7 +520,7 @@ NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> &
|
|||
parameter_to_be_declared->get_parameter_value(),
|
||||
rcl_interfaces::msg::ParameterDescriptor(), // Implicit declare uses default descriptor.
|
||||
staged_parameter_changes,
|
||||
initial_parameter_values_,
|
||||
parameter_overrides_,
|
||||
nullptr, // callback is explicitly null, so that it is called only once, when setting below.
|
||||
¶meter_event_msg);
|
||||
if (!result.successful) {
|
||||
|
@ -840,7 +840,7 @@ NodeParameters::register_param_change_callback(ParametersCallbackFunction callba
|
|||
#endif
|
||||
|
||||
const std::map<std::string, rclcpp::ParameterValue> &
|
||||
NodeParameters::get_initial_parameter_values() const
|
||||
NodeParameters::get_parameter_overrides() const
|
||||
{
|
||||
return initial_parameter_values_;
|
||||
return parameter_overrides_;
|
||||
}
|
||||
|
|
|
@ -67,14 +67,14 @@ NodeOptions::operator=(const NodeOptions & other)
|
|||
if (this != &other) {
|
||||
this->context_ = other.context_;
|
||||
this->arguments_ = other.arguments_;
|
||||
this->initial_parameters_ = other.initial_parameters_;
|
||||
this->parameter_overrides_ = other.parameter_overrides_;
|
||||
this->use_global_arguments_ = other.use_global_arguments_;
|
||||
this->use_intra_process_comms_ = other.use_intra_process_comms_;
|
||||
this->start_parameter_services_ = other.start_parameter_services_;
|
||||
this->allocator_ = other.allocator_;
|
||||
this->allow_undeclared_parameters_ = other.allow_undeclared_parameters_;
|
||||
this->automatically_declare_initial_parameters_ =
|
||||
other.automatically_declare_initial_parameters_;
|
||||
this->automatically_declare_parameters_from_overrides_ =
|
||||
other.automatically_declare_parameters_from_overrides_;
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
|
@ -142,21 +142,21 @@ NodeOptions::arguments(const std::vector<std::string> & arguments)
|
|||
}
|
||||
|
||||
std::vector<rclcpp::Parameter> &
|
||||
NodeOptions::initial_parameters()
|
||||
NodeOptions::parameter_overrides()
|
||||
{
|
||||
return this->initial_parameters_;
|
||||
return this->parameter_overrides_;
|
||||
}
|
||||
|
||||
const std::vector<rclcpp::Parameter> &
|
||||
NodeOptions::initial_parameters() const
|
||||
NodeOptions::parameter_overrides() const
|
||||
{
|
||||
return this->initial_parameters_;
|
||||
return this->parameter_overrides_;
|
||||
}
|
||||
|
||||
NodeOptions &
|
||||
NodeOptions::initial_parameters(const std::vector<rclcpp::Parameter> & initial_parameters)
|
||||
NodeOptions::parameter_overrides(const std::vector<rclcpp::Parameter> & parameter_overrides)
|
||||
{
|
||||
this->initial_parameters_ = initial_parameters;
|
||||
this->parameter_overrides_ = parameter_overrides;
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
@ -254,16 +254,17 @@ NodeOptions::allow_undeclared_parameters(bool allow_undeclared_parameters)
|
|||
}
|
||||
|
||||
bool
|
||||
NodeOptions::automatically_declare_initial_parameters() const
|
||||
NodeOptions::automatically_declare_parameters_from_overrides() const
|
||||
{
|
||||
return this->automatically_declare_initial_parameters_;
|
||||
return this->automatically_declare_parameters_from_overrides_;
|
||||
}
|
||||
|
||||
NodeOptions &
|
||||
NodeOptions::automatically_declare_initial_parameters(
|
||||
bool automatically_declare_initial_parameters)
|
||||
NodeOptions::automatically_declare_parameters_from_overrides(
|
||||
bool automatically_declare_parameters_from_overrides)
|
||||
{
|
||||
this->automatically_declare_initial_parameters_ = automatically_declare_initial_parameters;
|
||||
this->automatically_declare_parameters_from_overrides_ =
|
||||
automatically_declare_parameters_from_overrides;
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
|
|
@ -365,8 +365,10 @@ TEST_F(TestNode, declare_parameter_with_no_initial_values) {
|
|||
TEST_F(TestNode, declare_parameter_with_initial_values) {
|
||||
// test cases with initial values
|
||||
rclcpp::NodeOptions no;
|
||||
no.initial_parameters({
|
||||
no.parameter_overrides({
|
||||
{"parameter_no_default", 42},
|
||||
{"parameter_no_default_set", 42},
|
||||
{"parameter_no_default_set_cvref", 42},
|
||||
{"parameter_and_default", 42},
|
||||
{"parameter_custom", 42},
|
||||
{"parameter_template", 42},
|
||||
|
@ -381,6 +383,25 @@ TEST_F(TestNode, declare_parameter_with_initial_values) {
|
|||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);
|
||||
EXPECT_EQ(value.get<int>(), 42);
|
||||
}
|
||||
{
|
||||
// no default, with initial, and set after
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_no_default_set");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);
|
||||
EXPECT_EQ(value.get<int>(), 42);
|
||||
// check that the value is changed after a set
|
||||
node->set_parameter({"parameter_no_default_set", 44});
|
||||
EXPECT_EQ(node->get_parameter("parameter_no_default_set").get_value<int>(), 44);
|
||||
}
|
||||
{
|
||||
// no default, with initial
|
||||
const rclcpp::ParameterValue & value =
|
||||
node->declare_parameter("parameter_no_default_set_cvref");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);
|
||||
EXPECT_EQ(value.get<int>(), 42);
|
||||
// check that the value is changed after a set
|
||||
node->set_parameter({"parameter_no_default_set_cvref", 44});
|
||||
EXPECT_EQ(value.get<int>(), 44);
|
||||
}
|
||||
{
|
||||
// int default, with initial
|
||||
rclcpp::ParameterValue default_value(43);
|
||||
|
|
|
@ -150,7 +150,7 @@ ComponentManager::OnLoadNode(
|
|||
|
||||
auto options = rclcpp::NodeOptions()
|
||||
.use_global_arguments(false)
|
||||
.initial_parameters(parameters)
|
||||
.parameter_overrides(parameters)
|
||||
.arguments(remap_rules);
|
||||
|
||||
auto node_id = unique_id++;
|
||||
|
|
|
@ -91,13 +91,13 @@ LifecycleNode::LifecycleNode(
|
|||
node_topics_,
|
||||
node_services_,
|
||||
node_clock_,
|
||||
options.initial_parameters(),
|
||||
options.parameter_overrides(),
|
||||
options.start_parameter_services(),
|
||||
options.start_parameter_event_publisher(),
|
||||
options.parameter_event_qos(),
|
||||
options.parameter_event_publisher_options(),
|
||||
options.allow_undeclared_parameters(),
|
||||
options.automatically_declare_initial_parameters()
|
||||
options.automatically_declare_parameters_from_overrides()
|
||||
)),
|
||||
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
|
||||
node_base_,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue