Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ParameterUninitializedException on accessing parameter that is not yet set crashes node #1030

Closed
Achllle opened this issue Oct 27, 2022 · 10 comments
Labels
bug Something isn't working

Comments

@Achllle
Copy link
Contributor

Achllle commented Oct 27, 2022

Bug report

I'm not sure if this is a bug or a feature. When you try to access a parameter on a node from the CLI or from another node, the node hosting the parameter will crash rather than return an error message.

Required Info:

  • Operating System:
    • ros:galactic and ros:rolling docker images
  • Installation type:
    • docker pull ros:rolling
  • DDS implementation:
    • defaults
  • Client library (if applicable):
    • rclpy

Steps to reproduce issue

  1. follow instructions from official tutorial
  2. modify the code to use an uninitialized parameter as follows:
import rclpy
from rclpy.node import Node
from rclpy.parameter import Parameter
from rcl_interfaces.msg import SetParametersResult


class MinimalParam(Node):
    def __init__(self):
        super().__init__('minimal_param_node')
        self.log = self.get_logger()
        self.declare_parameter('my_parameter', Parameter.Type.STRING)

        self.add_on_set_parameters_callback(self.callback)

    def callback(self, parameters):
        for p in parameters:
            if p.name == 'my_parameter':
                self.log.info(f"Got my_parameter: {p.value}")
        return SetParametersResult(successful=True)


def main():
    rclpy.init()
    node = MinimalParam()
    rclpy.spin(node)

if __name__ == '__main__':
    main()
  1. build and run this node
  2. get the parameter from a different terminal using the CLI: ros2 param get /minimal_param_node my_parameter

Expected behavior

  • The set param call returns with successful=False and reason="parameter 'my_parameter' not initialized yet"
  • The node doesn't crash

Actual behavior

  • The set param call hangs
  • The node crashes with log:
Traceback (most recent call last):   
  File "/root/ros2_ws/install/python_parameters/lib/python_parameters/minimal_param_node", line 33, in <module>
    sys.exit(load_entry_point('python-parameters', 'console_scripts', 'minimal_param_node')())
  File "/root/ros2_ws/build/python_parameters/python_parameters/python_parameters_node.py", line 25, in main 
    rclpy.spin(node)      
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/__init__.py", line 222, in spin                                                                                                                                 
    executor.spin_once()                            
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 712, in spin_once                                                                                                                           
    raise handler.exception()                                                                                   
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/task.py", line 239, in __call__                                                                                                                                 
    self._handler.send(None)         
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 418, in handler                                                                                                                             
    await call_coroutine(entity, arg)            
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 372, in _execute_service
    response = await await_or_execute(srv.callback, request, srv.srv_type.Response())
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/executors.py", line 107, in await_or_execute                                                                                                                    
    return callback(*args)                                                                                                                                                                                                       
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/parameter_service.py", line 82, in _get_parameters_callback
    param = node.get_parameter(name)
  File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/node.py", line 598, in get_parameter          
    raise ParameterUninitializedException(name)                                                                 
rclpy.exceptions.ParameterUninitializedException: The parameter 'my_parameter' is not initialized  

Additional information

I consider the node crashing undesired behavior in this scenario since it explicitly requires the user to wrap rclpy.spin() or equivalent in some try-catch loop. I can see several use cases for this, for example when a different node is responsible for managing another node's parameters or wants to get information of another node's parameters.

@Barry-Xu-2018
Copy link
Contributor

Barry-Xu-2018 commented Oct 28, 2022

Yeah. Comparing rclpp, rclpy has different behaviors.
I incline to keep the same behavior as rclcpp.

According to the current implementation, rclpy doesn't support just setting the type.

self.declare_parameter('my_parameter', Parameter.Type.STRING)

will execute below code (value is None and without type)

parameter_list.append(Parameter(name, value=value))

For no type case, it tries to get type via input value.

def __init__(self, name, type_=None, value=None):
if type_ is None:
# This will raise a TypeError if it is not possible to get a type from the value.
type_ = Parameter.Type.from_parameter_value(value)

Since value is None, type is set No Set

if parameter_value is None:
return Parameter.Type.NOT_SET

So an exception is thrown while get parameter

rclpy/rclpy/rclpy/node.py

Lines 667 to 676 in 3d8547a

if (
parameter.type_ != Parameter.Type.NOT_SET or
self._descriptors[name].dynamic_typing
):
return self._parameters[name]
# Statically typed, uninitialized parameter
raise ParameterUninitializedException(name)
elif self._allow_undeclared_parameters:
return Parameter(name, Parameter.Type.NOT_SET, None)
else:

For current implementation of class Parameter, if value is None, the type must be Not Set

def check(self, parameter_value):
if Parameter.Type.NOT_SET == self:
return parameter_value is None
if Parameter.Type.BOOL == self:
return isinstance(parameter_value, bool)
if Parameter.Type.INTEGER == self:
return isinstance(parameter_value, int)
if Parameter.Type.DOUBLE == self:
return isinstance(parameter_value, float)
if Parameter.Type.STRING == self:
return isinstance(parameter_value, str)
if Parameter.Type.BYTE_ARRAY == self:
return isinstance(parameter_value, (list, tuple)) and \
all(isinstance(v, bytes) and len(v) == 1 for v in parameter_value)
if Parameter.Type.BOOL_ARRAY == self:
return isinstance(parameter_value, (list, tuple)) and \
all(isinstance(v, bool) for v in parameter_value)
if Parameter.Type.INTEGER_ARRAY == self:
return isinstance(parameter_value, (list, tuple, array.array)) and \
all(isinstance(v, int) for v in parameter_value)
if Parameter.Type.DOUBLE_ARRAY == self:
return isinstance(parameter_value, (list, tuple, array.array)) and \
all(isinstance(v, float) for v in parameter_value)
if Parameter.Type.STRING_ARRAY == self:
return isinstance(parameter_value, (list, tuple)) and \
all(isinstance(v, str) for v in parameter_value)
return False

@clalancette
Copy link
Contributor

Yes, agreed with everything that @Barry-Xu-2018 said. Definitely a bug, and I think we should make it behave like rclcpp here.

@clalancette clalancette added the bug Something isn't working label Oct 28, 2022
@fujitatomoya
Copy link
Collaborator

@Barry-Xu-2018 @iuhilnehc-ynos can we address this issue? for me, this is more like security level issue, since we can crash the different process space.

fujitatomoya added a commit to fujitatomoya/ros2_test_prover that referenced this issue Oct 28, 2022
@Barry-Xu-2018
Copy link
Contributor

@fujitatomoya Yes. I will submit a PR to fix this.

@Barry-Xu-2018
Copy link
Contributor

During fixing this, I find a problem.

Refer to the implementation of rclcpp, it uses exception UninitializedStaticallyTypedParameterException (PR: ros2/rclcpp#1689). The check action is located at declaration function (For rclpy, current code does check at get_parameter()).
For UninitializedStaticallyTypedParameterException, it happens while type is specified and value isn't set for declaring parameter phase.

For rclpy, the definition of declaration function is

rclpy/rclpy/rclpy/node.py

Lines 343 to 349 in 3d8547a

def declare_parameter(
self,
name: str,
value: Any = None,
descriptor: Optional[ParameterDescriptor] = None,
ignore_override: bool = False
) -> Parameter:

The value can be a parameter value or parameter type.
The requirement for static type parameter is that the parameter value must be initialized.
But while value is a parameter type, parameter value cannot be input based on current interface.

For supporting static type, current interface have to be changed (break API).
Do you have any opinions on fixing? @clalancette @fujitatomoya

@iuhilnehc-ynos
Copy link
Contributor

I think what we need to do is to deal with the extra exception ParameterUninitializedException here

except ParameterNotDeclaredException:
.

@Barry-Xu-2018
Copy link
Contributor

Barry-Xu-2018 commented Oct 31, 2022

I think what we need to do is to deal with the extra exception ParameterUninitializedException here

Yes. Here we can deal with this exception.

The above comment (#1030 (comment)) describe a problem which uninitialized static type parameter can be declared in rclpy.
For this bug, this line self.declare_parameter('my_parameter', Parameter.Type.STRING) should raise an exception if uninitialized static type parameter cannot be declared.

Besides,
I checked the implementation of rclcpp. It doesn't throw exception ParameterUninitializedException while calling get_parameters callback.

https://github.com/ros2/rclcpp/blob/edbfe1404b24d0bc85ff88e8ff1f006670788e46/rclcpp/src/rclcpp/parameter_service.cpp#L36-L53

  get_parameters_service_ = create_service<rcl_interfaces::srv::GetParameters>(
    node_base, node_services,
    node_name + "/" + parameter_service_names::get_parameters,
    [node_params](
      const std::shared_ptr<rmw_request_id_t>,
      const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
      std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response)
    {
      try {
        auto parameters = node_params->get_parameters(request->names);
        for (const auto & param : parameters) {
          response->values.push_back(param.get_value_message());
        }
      } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) {
        RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what());
      }
    },
    qos_profile, nullptr);

For node_params->get_parameters()
https://github.com/ros2/rclcpp/blob/edbfe1404b24d0bc85ff88e8ff1f006670788e46/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp#L904-L925

std::vector<rclcpp::Parameter>
NodeParameters::get_parameters(const std::vector<std::string> & names) const
{
  std::lock_guard<std::recursive_mutex> lock(mutex_);
  std::vector<rclcpp::Parameter> results;
  results.reserve(names.size());

  for (auto & name : names) {
    auto found_parameter = parameters_.find(name);
    if (found_parameter != parameters_.cend()) {
      // found
      results.emplace_back(name, found_parameter->second.value);
    } else if (this->allow_undeclared_) {
      // not found, but undeclared allowed
      results.emplace_back(name, rclcpp::ParameterValue());
    } else {
      // not found, and undeclared are not allowed
      throw rclcpp::exceptions::ParameterNotDeclaredException(name);
    }
  }
  return results;
}

@fujitatomoya
Copy link
Collaborator

For supporting static type, current interface have to be changed (break API).

I believe that is the specification, so we need to change the API if we have to.

CC: @ivanpauno @clalancette @wjwwood

@Barry-Xu-2018
Copy link
Contributor

In rclcpp, UninitializedStaticallyTypedParameterException is only used for this declaration. The return is the value of parameter.

https://github.com/ros2/rclcpp/blob/edbfe1404b24d0bc85ff88e8ff1f006670788e46/rclcpp/include/rclcpp/node_impl.hpp#L262-L282

template<typename ParameterT>
auto
Node::declare_parameter(
  const std::string & name,
  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
  bool ignore_override)
{
  // get advantage of parameter value template magic to get
  // the correct rclcpp::ParameterType from ParameterT
  rclcpp::ParameterValue value{ParameterT{}};
  try {
    return this->declare_parameter(
      name,
      value.get_type(),
      parameter_descriptor,
      ignore_override
    ).get<ParameterT>();
  } catch (const ParameterTypeException &) {
    throw exceptions::UninitializedStaticallyTypedParameterException(name);
  }
}

this->declare_parameter() return rclcpp::ParameterValue which store the type and value of a parameter.
get() throws an exception ParameterTypeException while value_.type is NO_SET.
https://github.com/ros2/rclcpp/blob/edbfe1404b24d0bc85ff88e8ff1f006670788e46/rclcpp/include/rclcpp/parameter_value.hpp#L145-L247
This is why UninitializedStaticallyTypedParameterException is used.

For rclpy, it provide interface

rclpy/rclpy/rclpy/node.py

Lines 343 to 349 in 3d8547a

def declare_parameter(
self,
name: str,
value: Any = None,
descriptor: Optional[ParameterDescriptor] = None,
ignore_override: bool = False
) -> Parameter:

The returned value is Parameter which doesn't only represent a parameter value. So UninitializedStaticallyTypedParameterException is unnecessary for rclpy.

We can keep current API. User can do self.declare_parameter('my_parameter', Parameter.Type.STRING). During declariation process, not report the exception ParameterUninitializedException. Instead, report this exception while user try to get parameter value (Current implementation). If get action from paramter service, we ignore this exception and return parameter (This step fixs this bug).
What do you think ? @fujitatomoya @ivanpauno @clalancette @wjwwood

@ivanpauno
Copy link
Member

I'm not sure if this is a bug or a feature. When you try to access a parameter on a node from the CLI or from another node, the node hosting the parameter will crash rather than return an error message.

It should not crash.
It should respond with an error and log and info message IMO.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

6 participants