Skip to content

Allow declaring uninitialized parameters#798

Merged
jacobperron merged 7 commits intomasterfrom
jacob/uninitialized_parameters
May 19, 2021
Merged

Allow declaring uninitialized parameters#798
jacobperron merged 7 commits intomasterfrom
jacob/uninitialized_parameters

Conversation

@jacobperron
Copy link
Copy Markdown
Member

Parameters can now be declared without a default value and without an override.
Attempting to access a statically typed parameter that does not have value will raise an exception.
Getting dynamically typed parameters will return an unset parameter value.

This change is equivalent to that made in rclcpp: ros2/rclcpp#1673

Parameters can now be declared without a default value and without an override.
Attempting to access a statically typed parameter that does not have value will raise an exception.
Getting dynamically typed parameters will return an unset parameter value.

This change is equivalent to that made in rclcpp: ros2/rclcpp#1673

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
@jacobperron jacobperron requested review from ivanpauno and sloretz May 18, 2021 21:10
Signed-off-by: Jacob Perron <jacob@openrobotics.org>
parameters: List[Union[
Tuple[str],
Tuple[str, Parameter.Type],
Tuple[str, Any],
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

wasn't this for passing a value, e.g.: declare_parameters('', [('my_param', 5)])?

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

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

I think the annotation was incorrect before. IIUC, we only expect a tuple up to length 3. The last value of the tuple can have type ParameterDescriptor or Any (for the case of passing a value).

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

('baz', 2.41),

We actually can be more specific than using Any, I think Union[int, float, str, bytes, None] would be fine

Copy link
Copy Markdown
Member

@wjwwood wjwwood left a comment

Choose a reason for hiding this comment

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

lgtm, with green CI and some manual testing to check for sanity.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
Signed-off-by: Jacob Perron <jacob@openrobotics.org>
Signed-off-by: Jacob Perron <jacob@openrobotics.org>
This is the same behavior as rclcpp.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
@jacobperron
Copy link
Copy Markdown
Member Author

Thanks for the reviews. I think I've addressed everything. PTAL.

Copy link
Copy Markdown
Member

@ivanpauno ivanpauno left a comment

Choose a reason for hiding this comment

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

LGTM with green CI

@ivanpauno
Copy link
Copy Markdown
Member

CI:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • macOS Build Status
  • Windows Build Status

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
@jacobperron
Copy link
Copy Markdown
Member Author

Thanks for triggering CI!
I thought the PR job would catch that flake8 error 🤷‍♂️

@jacobperron
Copy link
Copy Markdown
Member Author

Just retriggering Linux to confirm the linter is happy now: Build Status

@jacobperron jacobperron merged commit 38a4088 into master May 19, 2021
@delete-merged-branch delete-merged-branch bot deleted the jacob/uninitialized_parameters branch May 19, 2021 19:29
jacobperron added a commit that referenced this pull request May 19, 2021
* Allow declaring uninitialized parameters

Parameters can now be declared without a default value and without an override.
Attempting to access a statically typed parameter that does not have value will raise an exception.
Getting dynamically typed parameters will return an unset parameter value.

This change is equivalent to that made in rclcpp: ros2/rclcpp#1673

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Fix flake8

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Minor refactor

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Don't allow static parameters to be undeclared

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Return alternative for uninitialized parameters in get_parameter_or

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Ditto for dynamic parameters

This is the same behavior as rclcpp.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Fix lint

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
jacobperron added a commit that referenced this pull request May 20, 2021
* Allow declaring uninitialized parameters

Parameters can now be declared without a default value and without an override.
Attempting to access a statically typed parameter that does not have value will raise an exception.
Getting dynamically typed parameters will return an unset parameter value.

This change is equivalent to that made in rclcpp: ros2/rclcpp#1673

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Fix flake8

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Minor refactor

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Don't allow static parameters to be undeclared

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Return alternative for uninitialized parameters in get_parameter_or

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Ditto for dynamic parameters

This is the same behavior as rclcpp.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Fix lint

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants