if (!parameters_interface_->has_parameter(prefix_ + "{{parameter_name}}")) {
{%- filter indent(width=4) %}
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.description = {{parameter_description | valid_string_cpp}};
descriptor.read_only = {{parameter_read_only}};
{%- if parameter_additional_constraints|length %}
descriptor.additional_constraints = {{parameter_additional_constraints | valid_string_cpp}};
{% endif -%}
{%- if "DOUBLE" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.floating_point_range.resize(1);
descriptor.floating_point_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<double>::lowest()"}};
descriptor.floating_point_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<double>::max()"}};
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- set range = namespace(lower=None, upper=None) %}
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if validation.arguments|length == 2 %}
{%- set range.lower = validation.arguments[0] %}
{%- set range.upper = validation.arguments[1] %}
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.lower = validation.arguments[0] %}
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
{%- set range.upper = validation.arguments[0] %}
{%- endif %}
{%- endfor %}
{%- if range.lower is not none or range.upper is not none %}
descriptor.integer_range.resize(1);
descriptor.integer_range.at(0).from_value = {{range.lower if range.lower is not none else "std::numeric_limits<int64_t>::lowest()"}};
descriptor.integer_range.at(0).to_value = {{range.upper if range.upper is not none else "std::numeric_limits<int64_t>::max()"}};
{%- endif %}
{%- endif %}
{%- if not parameter_value|length %}
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
{%- if parameter_value|length %}
auto parameter = to_parameter_value(updated_params.{{parameter_value}});
{% endif -%}
parameters_interface_->declare_parameter(prefix_ + "{{parameter_name}}", parameter, descriptor);
{% endfilter -%}
}
