Comments (9)
i may be mistaken something, but here are my comments.
are you suggesting we should remove allow_undeclared_parameters
flag and rclcpp::exceptions::ParameterNotDeclaredException
at all?
either allow_undeclared_parameters
is true or false, we can get, type, set, list and describe parameters via service with default elements for those undeclared parameters? so the remote node can set any undeclared parameter via parameter service?
or allow_undeclared_parameters
is only effective in set_parameter
request? but the question is how we can know that parameter is not actually declared or just set the default values as dynamic typed parameter. this eventually causes the ParameterNotDeclared
result for the application if that is undeclared.
i think that application can call list
service 1st to know what parameters are declared and then call other services.
While implementing parameter services for rclrs, we noticed that the behavior of rclcpp and rclpy is inconsistent with the documentation of rcl_interfaces/srv/GetParameterTypes which says it returns a "List of types which is the same length and order as the provided names." and also "ParameterType.PARAMETER_NOT_SET indicates that the parameter is not currently set.".
this needs to be fixed and consistent, either way we go. thank you for pointing this out.
Returning an empty array is unhelpful whether the client is a human or a program. It provides the least amount of information possible in response to the service request and forces clients to always make multiple service requests in order to reliably detect the values of parameters.
true.
but server can response quick to protect itself. if undeclared parameter request is included, it can return immediately with empty result, because that is not permitted operation for the parameters that this node possesses. otherwise, server needs to deal with many default elements for each request from multiple clients.
The concept of declared / undeclared does not even exist in rcl_interfaces. I see parameter declaration as an implementation detail for parameter management that's internal to a node. Clients of parameter services should not generally need to be concerned about parameter declaration settings within a node that they are querying, but the current behavior is leaking that abstraction into the behavior of the parameter services.
based on this description, remote nodes can set any undeclared parameters via service request. i am not sure if this is good idea.
An undeclared parameter in an allow_undeclared_parameters(false) node can be thought of as unsettable, and therefore its value is just permanently unset. Naturally this means any client asking for the value of that parameter should be told that the value of the parameter is unset.
i am not really following this, can you rephrase this a bit?
what if that is declared parameter with dynamic typing? at the node initialization it cannot specify the type, but later on it sets the type and value to align with connected sensor mode and types.
If we guarantee that the response array is always the same size as the request array, we reduce the likelihood that clients will write an accidental buffer overflow while iterating through the request and response arrays simultaneously because they weren't aware of the service behavior diverging due to parameter declaration.
i understand this, but technically this is just a buffer overflow bug in the application...
Furthermore if a client calls rcl_interfaces/srv/SetParameters with an undeclared parameter on a node with allow_undeclared_parameters(false) then the client libraries should return something like { successful: false, reason: "Parameter is not declared by the node, which only allows declared parameters" } where the reason value is a fixed and consistent string literal across all client libraries so that parameter service clients can do a simple string comparison against. I would recommend defining the string literal inside of rcl_interfaces/msg/SetParametersResult with a name like REASON_UNDECLARED_PARAMETER. Currently rclcpp and rclpy produce different reason values for this same situation. Admittedly the service documentation says that reason should only be read by humans, but I think this particular case warrants a fixed and consistent value.
totally agree on this.
from rclcpp.
are you suggesting we should remove allow_undeclared_parameters flag and rclcpp::exceptions::ParameterNotDeclaredException at all?
This issue report is only concerned with getting the behavior of the parameter services of the client libraries to conform to the documentation of the services in node_interfaces
. The implementation and API of the client libraries are a separate matter.
To make this discussion easier, I've gone ahead and implemented the changes I recommend in a draft PR #2515
There are only two things I left out of the draft PR that I think could make the situation better, but they would be somewhat disruptive, so I think there should be some buy-in before trying to do it:
- The error message given for
reason
when trying to set an undeclared parameter should be a constant value inrcl_interfaces/msg/SetParametersResult
. In the draft it's simply a magic string literal. - The use of
node_params->describe_parameters
is clunky, feeding in one parameter name at a time. This could be improved if we do one of the following:- Change the behavior of
NodeParametersInterface::describe_parameters
to not care about whether undeclared parameters are allowed. - Change the API of
NodeParameterInterface::describe_parameters
by adding a bool argument to ignore whether or not declared parameters are allowed. - Add a
describe_parameter
method toNodeParameterInterface
.
- Change the behavior of
how we can know that parameter is not actually declared or just set the default values as dynamic typed parameter
If "we" are the client that's calling _/get_parameters
, then I would say the difference shouldn't matter. Either way the value is simply unset. On the other hand if "we" are the client that's calling _/set_parameters
then you'll find out the value cannot be set by the { sucessful: false, ... }
response that you receive. There are many reasons that a _/set_parameters
request might fail to set a value, and the allow_undeclared_parameters(false)
situation is only one of them.
otherwise, server needs to deal with many default elements for each request from multiple clients.
You'll see in my draft PR that we actually cut down on complexity and lines of code with my suggestion, except for describe_parameters
because of some rigidity in the NodeParameterInterface::describe_parameters
API.
based on this description, remote nodes can set any undeclared parameters via service request. i am not sure if this is good idea.
Users can set parameter handler callbacks that can reject an attempt to set the value of a parameter for any reason. allow_undeclared_parameters(false)
would simply be one reason to reject an attempt to set a parameter to a certain value. I'm not actually proposing any change here except to standardize the reason
given in this situation.
what if that is declared parameter with dynamic typing? at the node initialization it cannot specify the type, but later on it sets the type and value to align with connected sensor mode and types.
From the perspective of rcl_interfaces
parameter services, there is no difference between the value or type of an unset dynamic parameter versus an undeclared parameter. You would only see a difference in two places:
- The unset dynamic parameter will appear during
_/list_parameters
whereas an undeclared parameter will not - The unset dynamic parameter can have its value changed during
_/set_parameters
whereas an undeclared parameter in anallow_undeclared_parameters(false)
node cannot
i understand this, but technically this is just a buffer overflow bug in the application...
I would argue that if the application is complying with the documentation of rcl_interfaces
(which says the size of the response vector will always match the size of the request vector) while rclcpp
and rclpy
are not complying with the documentation, then the bug is in rclcpp
and rclpy
.
from rclcpp.
To make this discussion easier, I've gone ahead and implemented the changes I recommend in a draft PR #2515
thanks, i will take a look!
The error message given for reason when trying to set an undeclared parameter should be a constant value in rcl_interfaces/msg/SetParametersResult.
agree, so that application can check against it.
The use of node_params->describe_parameters is clunky, feeding in one parameter name at a time. This could be improved if we do one of the following
sounds good.
The unset dynamic parameter will appear during _/list_parameters whereas an undeclared parameter will not
that is why originally i was thinking this comes down to call list_parameter
service to know declared parameters, and then call other services.
I am not really sure returning PARAMETER_NOT_SET
values for the undeclared parameters via service would help this situation, that is my original question.
Just idea, what if we have PARAMETER_NOT_DECLARED
state? and return the same size of array requested via service? does that help the application?
I would argue that if the application is complying with the documentation of rcl_interfaces (which says the size of the response vector will always match the size of the request vector) while rclcpp and rclpy are not complying with the documentation, then the bug is in rclcpp and rclpy.
yes, this is inconsistent and bug in the system. we need to fix for sure. what i meant is after fixing this inconsistency...
from rclcpp.
Just idea, what if we have PARAMETER_NOT_DECLARED state?
I don't think it makes sense to consider "Undeclared" a different type from "Unset". Consider a node that has allow_undeclared_parameters(true)
instead of (false)
. Would that node return NOT_DECLARED
or would it return UNSET
when a user queries for an undeclared parameter? It seems to me like you're trying to avoid returning "Unset" because you want to indicate to the caller that the parameter cannot be given a value, but if the node has allow_undeclared_parameters(true)
then any undeclared parameter can be set, which would then make it misleading or at least ambiguous to return NOT_DECLARED
.
Rather than thinking about "undeclared" as its own type I would recommend thinking in terms of constraints on the values. Suppose I write a node and declare a string-type parameter called DEVICE_NAME
. I could choose to add a custom parameter event handler that will only allow fully-uppercase string values for DEVICE_NAME
. If a _/set_parameters
client tries to give the DEVICE_NAME
parameter a value with any lowercase characters in it, they would receive a response of { successful: false, reason: "ONLY UPPERCASE PLEASE" }
. I am allowed to do this and parameter clients are expected to handle it by examining the reason
given when an attempt to set the value fails. We would not suggest adding a new type to rcl_interfaces
called UPPERCASE_STRING
, because there is nothing special about the data type for my parameter, there are simply some constraints on what values it can have.
Similarly, there is nothing special about the data type of an undeclared: The data type of any undeclared parameter is the null set, also called the unit type, which rcl_interfaces
expresses as "Unset". The only thing that is special about undeclared parameters is that when a node has the allow_undeclared_parameters(false)
setting, the undeclared parameters are constrained to remain null. Nothing is different about their actual data type, and whether or not they behave any differently than a regular "Unset" type depends on the allow_undeclared_parameters
node setting which isn't generally visible outside of the node.
In general I don't think there's a point to treating the allow_undeclared_parameters(false)
constraints as a special case when ultimately users can apply any constraints they want to any parameters they want, declared or undeclared, and parameter clients need to be prepared to recognize and handle any arbitrary constraints anyway.
Undeclared parameters can be thought of as dynamic-type parameters which currently have a value type of "Unset", and the allow_undeclared_parameters
node setting determines whether those undeclared parameters are constrained to remain unset or can be given a new value type by parameter clients. The { successful: false, reason: ... }
response of _/set_parameters
is the mechanism in rcl_interfaces
for communicating the constraints on parameter values, and I think that's sufficient for undeclared parameters in allow_undeclared_parameters(false)
nodes.
from rclcpp.
that is why originally i was thinking this comes down to call list_parameter service to know declared parameters, and then call other services.
I am not really sure returning PARAMETER_NOT_SET values for the undeclared parameters via service would help this situation, that is my original question.
The responsibilities of the different parameter services are pretty clear in my mind:
- If a client just wants to know the values of some parameters, they check
_/get_parameters
. If they don't care about why some parameters may be unset, then this is sufficient. - If a client just wants to know which parameters are declared, they check
_/list_parameters
. - If a client wants to know whether an unset parameter has that value because it's undeclared, then they check both
_/get_parameters
and_/list_parameters
. - If a client wants to set the value of a parameter (which is the only reason they should really care about declared/undeclared) then they will call
_/set_parameters
when the parameter does not have the value that they want, and then they will discover that it cannot be set based on the response. In this case it would be enough for them to just follow this sequence:- Call
_/get_parameters
and find out that the parameter they care about is not the desired value because it is currently unset - Call
_/set_parameters
to try to set the desired value and find out from the service response that it cannot be set because it is undeclared on a node that hasallow_undeclared_parameters(false)
- Handle this in whatever way is appropriate for their application
- Call
from rclcpp.
thank you very much iterating and sharing thoughts, i was checking myself what could be missing here. but now it is clear to me!
Consider a node that has allow_undeclared_parameters(true) instead of (false). Would that node return NOT_DECLARED or would it return UNSET when a user queries for an undeclared parameter?
i was thinking that, NOT_DECLARED
is assigned to undeclared parameters regardless of allow_undeclared_parameters flag. so the user application can know what is declared or undeclared at least.
but as you mentioned, this can be more complication for user application. user application perspective, there is no difference between NOT_SET
and NOT_DECLARED
...
In general I don't think there's a point to treating the allow_undeclared_parameters(false) constraints as a special case when ultimately users can apply any constraints they want to any parameters they want
i think this is originally developed exclude any parameters to be set that do not belong to node. but true, we can do this with default add_on_set_parameters_callback
callback, and reject all undeclared parameters to be set.
The responsibilities of the different parameter services are pretty clear in my mind:
sounds reasonable. i am now inclined to take this consistent behavior along with set_parameters
sevice to return the same size of requested array as interface describes.
you already opened a couple of draft PRs, #2515 and ros2/rcl_interfaces#164, thanks. (i think we need to update rclpy
aligned with #2515)
before moving to the implementation, can we keep this open for a bit to get more feedbacks?
@wjwwood @mjcarroll @alsora @clalancette what do you think?
from rclcpp.
@mxgrey i added this to Client WG meeting. hopefully we can get some feedback from there.
from rclcpp.
Reporting here my thoughts (discussed in the client library WG).
TL;DR: I think we should change the implementation to always match the documentation.
I agree that the current behavior is not intuitive, and indeed we stumbled on it also in our application.
In particular, having different results depending on the value of allow_undeclared_parameters
.
As an additional point, the current implementation (which returns an empty vector if something is not present) doesn't work well with "optional parameters".
For example, if I'm interested in a bunch of parameters and I don't know which ones are declared or not, the only option is currently to request them one by one, because if requesting more than on at the same time I would get an empty vector if any was missing.
I also agree on having an explicit success
field in the service response.
I think that it's good practice for all services to have that (and also a message
field).
Note that this change will break the user applications (for example in my application we currently check for an empty vector to know if the service failed...), but I think it's ok and worth to do it.
from rclcpp.
My main blocker right now for finishing up the PRs for this is how to improve the description fetching.
The essential problem is that NodeParametersInterface::describe_parameters
has the exception-based behavior baked in pretty strongly, which makes it awkward to implement the service with it correctly. I have three proposals for how to fix this, and would appreciate feedback from maintainers about which would be least controversial:
(1) Add a new argument to describe_parameters to override the behavior when allow_undeclared_parameters is false:
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(
const std::vector<std::string> & names,
bool override_allow_undeclared_false=false) const = 0;
(2) have a function that gets parameter descriptions one at a time, returning std::nullopt
when the parameter is undeclared:
std::optional<rcl_interfaces::msg::ParameterDescriptor>
describe_parameter(const std::string & name) const = 0;
(3) reimplement NodeParameters::describe_parameter
to just not behave differently under allow_undeclared_parameters(false)
, i.e. have it return blank unassigned-type descriptions just like the service describes, instead of throwing an exception.
Likely controversies:
- For (1) the argument name is clunky and confusing, and I can't think of a way to make it less confusing. Also this suggestion breaks the abstract interface API.
- For (2) there would be a lot of redundancy between
describe_parameter
anddescribe_parameters
. Also this forces all implementers of the interface to add this new function. - (3) would be the easiest and cleanest, but it would be inconsistent with the exception-driven behavior that the other rclcpp APIs currently have for undeclared parameters.
from rclcpp.
Related Issues (20)
- TimersManager doesn't follow ROS time HOT 2
- rclcpp_action: Provide enum class return ClientGoalHandle::get_status
- Callback works on Galactic but fails on Rolling - handle_message is not implemented for GenericSubscription HOT 1
- Clang warning: ordered comparison of function pointers (Rolling) HOT 1
- `-fanalyzer` warning: possible null dereference when using TypeAdapters HOT 4
- leak due to std::shared_ptr circular reference between Context and GuardCondition HOT 3
- :farmer: `rclcpp.test_executors` failing in Rolling and Jazzy CycloneDDS HOT 2
- rclcpp::Time(int64_t nanoseconds, ...) should check for negative time
- Regression : Executor::spin_some_impl is active waiting HOT 5
- Lifecycle destructor calls shutdown while in shuttingdown intermediate state HOT 45
- Backport PR2063 to Humble for Windows HOT 2
- Executor callbacks are no longer in a predictable order HOT 25
- '/clock' Topic cannot change each loop step time from simulation time HOT 10
- Program exits with code -11 when using async_send_request to set parameters in ROS 2 C++ client HOT 1
- Timer callbacks can be delayed when using simulation time HOT 4
- Possible regression in rcl preshutdown callbacks - context invalid? HOT 11
- Shutdown transition on base lifecycle node dtor may lead to segaults on subclass-registered shutdown callback HOT 6
- `on_shutdown` callback not called when `shutdown` transition is triggered on dtor HOT 2
- ABI/API Compliance Checker in github workflow HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from rclcpp.