Skip to content
14 changes: 2 additions & 12 deletions rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,16 +44,6 @@ namespace rclcpp
namespace node_interfaces
{

// Internal struct for holding useful info about parameters
struct ParameterInfo
{
/// Current value of the parameter.
rclcpp::ParameterValue value;

/// A description of the parameter
rcl_interfaces::msg::ParameterDescriptor descriptor;
};

// Internal RAII-style guard for mutation recursion
class ParameterMutationRecursionGuard
{
Expand Down Expand Up @@ -200,7 +190,7 @@ class NodeParameters : public NodeParametersInterface
remove_on_set_parameters_callback(const OnSetParametersCallbackHandle * const handler) override;

RCLCPP_PUBLIC
const std::map<std::string, rclcpp::ParameterValue> &
const std::map<std::string, ParameterInfo> &
get_parameter_overrides() const override;

using CallbacksContainerType = std::list<OnSetParametersCallbackHandle::WeakPtr>;
Expand All @@ -221,7 +211,7 @@ class NodeParameters : public NodeParametersInterface

std::map<std::string, ParameterInfo> parameters_;

std::map<std::string, rclcpp::ParameterValue> parameter_overrides_;
std::map<std::string, ParameterInfo> parameter_overrides_;

bool allow_undeclared_ = false;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,7 +228,7 @@ class NodeParametersInterface
/// Return the initial parameter values used by the NodeParameters to override default values.
RCLCPP_PUBLIC
virtual
const std::map<std::string, rclcpp::ParameterValue> &
const std::map<std::string, ParameterInfo> &
get_parameter_overrides() const = 0;
};

Expand Down
11 changes: 10 additions & 1 deletion rclcpp/include/rclcpp/parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <vector>

#include "rcl_interfaces/msg/parameter.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"
Expand All @@ -33,7 +34,15 @@ class Parameter;

namespace node_interfaces
{
struct ParameterInfo;
// Internal struct for holding useful info about parameters
struct ParameterInfo
{
/// Current value of the parameter.
rclcpp::ParameterValue value;

/// A description of the parameter
rcl_interfaces::msg::ParameterDescriptor descriptor;
};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bpwilcox meta: hmm, why not pushing this descriptor attribute into rclcpp::Parameter? Then we can use rclcpp::Parameter everywhere.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I do agree that you could put the descriptor in the rclcpp::Parameter object, however that seems to be a more far-reaching change than this PR, especially since many user-code uses rclcpp::Parameter. I think it is a good candidate for a follow-up PR.

} // namespace node_interfaces

namespace detail
Expand Down
13 changes: 12 additions & 1 deletion rclcpp/include/rclcpp/parameter_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,18 +20,23 @@

#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"

namespace rclcpp
{

/// A map of fully qualified node names to a list of parameters
using ParameterMap = std::unordered_map<std::string, std::vector<Parameter>>;
using rcl_interfaces::msg::ParameterDescriptor;
using ParameterAndDescriptor = std::unordered_map<std::string,
rclcpp::node_interfaces::ParameterInfo>;
using ParameterMap = std::unordered_map<std::string, ParameterAndDescriptor>;

/// Convert parameters from rcl_yaml_param_parser into C++ class instances.
/// \param[in] c_params C structures containing parameters for multiple nodes.
Expand All @@ -49,6 +54,12 @@ RCLCPP_PUBLIC
ParameterValue
parameter_value_from(const rcl_variant_t * const c_value);

RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterDescriptor
parameter_descriptor_from(
const char * const name,
const rcl_param_descriptor_t * const c_descriptor);

/// Get the ParameterMap from a yaml file.
/// \param[in] yaml_filename full name of the yaml file.
/// \returns an instance of a parameter map
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/src/rclcpp/detail/resolve_parameter_overrides.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,14 @@
#include "rclcpp/scope_exit.hpp"
#include "rclcpp/parameter_map.hpp"

std::map<std::string, rclcpp::ParameterValue>
std::map<std::string, rclcpp::node_interfaces::ParameterInfo>
rclcpp::detail::resolve_parameter_overrides(
const std::string & node_fqn,
const std::vector<rclcpp::Parameter> & parameter_overrides,
const rcl_arguments_t * local_args,
const rcl_arguments_t * global_args)
{
std::map<std::string, rclcpp::ParameterValue> result;
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> result;

// global before local so that local overwrites global
std::array<const rcl_arguments_t *, 2> argument_sources = {global_args, local_args};
Expand Down Expand Up @@ -59,9 +59,9 @@ rclcpp::detail::resolve_parameter_overrides(
for (const auto & node_name : node_matching_names) {
if (initial_map.count(node_name) > 0) {
// Combine parameter yaml files, overwriting values in older ones
for (const rclcpp::Parameter & param : initial_map.at(node_name)) {
result[param.get_name()] =
rclcpp::ParameterValue(param.get_value_message());
for (const auto & param : initial_map.at(node_name)) {
result[param.first] = param.second;
result[param.first].descriptor.dynamic_typing = true;
}
}
}
Expand All @@ -70,7 +70,7 @@ rclcpp::detail::resolve_parameter_overrides(

// parameter overrides passed to constructor will overwrite overrides from yaml file sources
for (auto & param : parameter_overrides) {
result[param.get_name()] =
result[param.get_name()].value =
rclcpp::ParameterValue(param.get_value_message());
}
return result;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/detail/resolve_parameter_overrides.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace detail
{
/// \internal Get the parameter overrides from the arguments.
RCLCPP_LOCAL
std::map<std::string, rclcpp::ParameterValue>
std::map<std::string, rclcpp::node_interfaces::ParameterInfo>
resolve_parameter_overrides(
const std::string & node_name,
const std::vector<rclcpp::Parameter> & parameter_overrides,
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ get_parameter_events_qos(
auto param_name = prefix + rclcpp::qos_policy_kind_to_cstr(policy);
auto it = parameter_overrides.find(param_name);
auto value = it != parameter_overrides.end() ?
it->second :
it->second.value :
rclcpp::detail::get_default_qos_param_value(policy, options.parameter_event_qos());
rclcpp::detail::apply_qos_override(policy, value, final_qos);
}
Expand Down
26 changes: 19 additions & 7 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,13 +102,14 @@ NodeParameters::NodeParameters(
// 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_parameters_from_overrides) {
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bpwilcox why the change?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've reverted this change, though I am still open to discussing the most appropriate behavior for dynamic_tuning field being set from a yaml file. For example, if you have a blackboard node and wanted to have a parameter become static typing, this change would overwrite. Before allowing yaml descriptor overrides, I'd agree it makes more sense to have parameters be dynamic typing when automatically declared, but now with this feature, I'm unsure if this should be the case.

for (const auto & pair : this->get_parameter_overrides()) {
if (!this->has_parameter(pair.first)) {
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor = pair.second.descriptor;
descriptor.dynamic_typing = true;
this->declare_parameter(
pair.first,
pair.second,
pair.second.value,
descriptor,
true);
}
Expand Down Expand Up @@ -332,7 +333,7 @@ __declare_parameter_common(
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
const std::map<std::string, rclcpp::ParameterValue> & overrides,
const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & overrides,
CallbacksContainerType & callback_container,
const OnParametersSetCallbackType & callback,
rcl_interfaces::msg::ParameterEvent * parameter_event_out,
Expand All @@ -345,8 +346,19 @@ __declare_parameter_common(
// Use the value from the overrides if available, otherwise use the default.
const rclcpp::ParameterValue * initial_value = &default_value;
auto overrides_it = overrides.find(name);

// If override for parameter value, use it
// If parameter override only, don't override descriptor
// If override for descriptor, use it
// If descriptor override only, don't override parameter value

if (!ignore_override && overrides_it != overrides.end()) {
initial_value = &overrides_it->second;
if (overrides_it->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) {
initial_value = &overrides_it->second.value;
}
if (overrides_it->second.descriptor.name != "") {
parameter_infos[name].descriptor = overrides_it->second.descriptor;
}
}

// If there is no initial value, then skip initialization
Expand Down Expand Up @@ -397,7 +409,7 @@ declare_parameter_helper(
rcl_interfaces::msg::ParameterDescriptor parameter_descriptor,
bool ignore_override,
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
const std::map<std::string, rclcpp::ParameterValue> & overrides,
const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & overrides,
CallbacksContainerType & callback_container,
const OnParametersSetCallbackType & callback,
rclcpp::Publisher<rcl_interfaces::msg::ParameterEvent> * events_publisher,
Expand Down Expand Up @@ -1002,7 +1014,7 @@ NodeParameters::add_on_set_parameters_callback(OnParametersSetCallbackType callb
return handle;
}

const std::map<std::string, rclcpp::ParameterValue> &
const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> &
NodeParameters::get_parameter_overrides() const
{
return parameter_overrides_;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -308,7 +308,7 @@ AsyncParametersClient::load_parameters(
(node_name == remote_name))
{
for (const auto & param : params.second) {
parameters.push_back(param);
parameters.push_back(rclcpp::Parameter(param.second));
}
}
}
Expand Down
105 changes: 100 additions & 5 deletions rclcpp/src/rclcpp/parameter_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <limits>
#include <string>
#include <vector>

Expand All @@ -21,6 +22,9 @@ using rclcpp::exceptions::InvalidParametersException;
using rclcpp::exceptions::InvalidParameterValueException;
using rclcpp::ParameterMap;
using rclcpp::ParameterValue;
using rcl_interfaces::msg::ParameterDescriptor;
using rcl_interfaces::msg::FloatingPointRange;
using rcl_interfaces::msg::IntegerRange;

ParameterMap
rclcpp::parameter_map_from(const rcl_params_t * const c_params)
Expand Down Expand Up @@ -49,11 +53,9 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params)
node_name = c_node_name;
}

const rcl_node_params_t * const c_params_node = &(c_params->params[n]);

std::vector<Parameter> & params_node = parameters[node_name];
params_node.reserve(c_params_node->num_params);
ParameterAndDescriptor & params = parameters[node_name];

const rcl_node_params_t * const c_params_node = &(c_params->params[n]);
for (size_t p = 0; p < c_params_node->num_params; ++p) {
const char * const c_param_name = c_params_node->parameter_names[p];
if (NULL == c_param_name) {
Expand All @@ -62,7 +64,21 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params)
throw InvalidParametersException(message);
}
const rcl_variant_t * const c_param_value = &(c_params_node->parameter_values[p]);
params_node.emplace_back(c_param_name, parameter_value_from(c_param_value));
params[c_param_name].value = parameter_value_from(c_param_value);
}

const rcl_node_params_descriptors_t * const c_param_descriptors_node =
&(c_params->descriptors[n]);
for (size_t p = 0; p < c_param_descriptors_node->num_descriptors; ++p) {
const char * const c_param_name = c_param_descriptors_node->parameter_names[p];
if (NULL == c_param_name) {
std::string message(
"At node " + std::to_string(n) + " parameter " + std::to_string(p) + " name is NULL");
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bpwilcox do we need an auxiliary variable?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The message string? Probably not needed, this was left from the previous code, not my additions.

throw InvalidParametersException(message);
}
const rcl_param_descriptor_t * const c_param_descriptor =
&(c_param_descriptors_node->parameter_descriptors[p]);
params[c_param_name].descriptor = parameter_descriptor_from(c_param_name, c_param_descriptor);
}
}
return parameters;
Expand Down Expand Up @@ -127,6 +143,85 @@ rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)
throw InvalidParameterValueException("No parameter value set");
}

ParameterDescriptor
rclcpp::parameter_descriptor_from(
const char * const name,
const rcl_param_descriptor_t * const c_param_descriptor)
{
if (NULL == c_param_descriptor) {
throw InvalidParameterValueException("Passed argument is NULL");
}
ParameterDescriptor p;

if (name) {
p.name = std::string(name);
}
if (c_param_descriptor->type) {
p.type = *(c_param_descriptor->type);
}
if (c_param_descriptor->description) {
p.description = std::string(c_param_descriptor->description);
}
if (c_param_descriptor->additional_constraints) {
p.additional_constraints = std::string(c_param_descriptor->additional_constraints);
}
if (c_param_descriptor->read_only) {
p.read_only = *(c_param_descriptor->read_only);
}

if (c_param_descriptor->dynamic_typing) {
p.dynamic_typing = *(c_param_descriptor->dynamic_typing);
}

if (c_param_descriptor->min_value_int || c_param_descriptor->max_value_int ||
c_param_descriptor->step_int)
{
if (c_param_descriptor->min_value_double || c_param_descriptor->max_value_double ||
c_param_descriptor->step_double)
{
throw InvalidParameterValueException(
"Mixed 'integer' and 'double' types not supported for parameter descriptor range");
}
IntegerRange i;
if (c_param_descriptor->min_value_int) {
i.from_value = *(c_param_descriptor->min_value_int);
} else {
i.from_value = std::numeric_limits<int64_t>::min();
}
if (c_param_descriptor->max_value_int) {
i.to_value = *(c_param_descriptor->max_value_int);
} else {
i.to_value = std::numeric_limits<int64_t>::max();
}
if (c_param_descriptor->step_int) {
i.step = *(c_param_descriptor->step_int);
}
p.integer_range.push_back(i);
} else if ( // NOLINT
c_param_descriptor->min_value_double ||
c_param_descriptor->max_value_double ||
c_param_descriptor->step_double)
{
FloatingPointRange f;
if (c_param_descriptor->min_value_double) {
f.from_value = *(c_param_descriptor->min_value_double);
} else {
f.from_value = std::numeric_limits<double>::lowest();
}
if (c_param_descriptor->max_value_double) {
f.to_value = *(c_param_descriptor->max_value_double);
} else {
f.to_value = std::numeric_limits<double>::max();
}
if (c_param_descriptor->step_double) {
f.step = *(c_param_descriptor->step_double);
}
p.floating_point_range.push_back(f);
}

return p;
}

ParameterMap
rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename)
{
Expand Down
Loading