Skip to content

Commit

Permalink
Merge branch 'release/0.7.0'
Browse files Browse the repository at this point in the history
  • Loading branch information
jara001 committed Apr 27, 2023
2 parents f095b26 + 60e7ccb commit f6ebfc8
Show file tree
Hide file tree
Showing 5 changed files with 110 additions and 19 deletions.
9 changes: 9 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,15 @@ All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](http://keepachangelog.com/).

## Unreleased
## 0.7.0 - 2023-04-27
### Added
- `reconfigure`:
- ROS2 is now supported.

### Removed
- `uninode`:
- Node no longer produces warnings when using unimplmented functions.

## 0.6.0 - 2022-08-24
### Added
- `reconfigure`:
Expand Down
17 changes: 12 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -256,16 +256,23 @@ To make your code runnable on `<= 0.4.0` stick to these rules:

#### ROS 2

Current implementation is not compatible with ROS2. Some parts are usable, however the reconfiguration part is not perfect. At least, the definition of the parameters and accessing their value seems working. Pull requests are welcome!

Since it requires `dynamic_reconfigure` messages, you can download them [here](https://github.com/jara001/dynamic_reconfigure).

If you want to test the reconfiguration, you have to pass the Node instance inside `node` argument:
To use reconfiguration utility in ROS2, you have to pass the Node instance inside `node` argument:

```python
P.reconfigure(node = node)
```

In the current implementation following features are not supported:
- enums,
- linked variables.

Because of the limitations of ROS2 API it is most likely that they will be never supported.

As from the ROS2 Parameter API side these features are currently not implemented:
- IntegerRange,
- FloatingPointRange,
- Arrays.


### Full example

Expand Down
8 changes: 0 additions & 8 deletions autopsy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -189,9 +189,6 @@ def __getattr__(self, name):
"""

if ROS_VERSION == 1:
if hasattr(rospy, name):
print ("[WARNING] Unsupported attribute 'rospy.%s'." % name)

return getattr(rospy, name)
else:
# Raise AttributeError
Expand All @@ -204,9 +201,4 @@ def __getattribute__(self, name):
Arguments:
name -- name of the attribute / method
"""

if ROS_VERSION == 2:
if not hasattr(NodeR1, name):
print ("[WARNING] Unsupported attribute 'self.%s'." % name)

return super(Node, self).__getattribute__(name)
93 changes: 88 additions & 5 deletions autopsy/reconfigure.py
Original file line number Diff line number Diff line change
Expand Up @@ -115,13 +115,26 @@ def limit_value(new_value):


# Message types
from dynamic_reconfigure.msg import ConfigDescription, Config, Group, ParamDescription, BoolParameter, IntParameter, StrParameter, DoubleParameter, GroupState
from dynamic_reconfigure.srv import Reconfigure

if autopsy.node.ROS_VERSION == 1:
from dynamic_reconfigure.msg import ConfigDescription, Config, Group, ParamDescription, BoolParameter, IntParameter, StrParameter, DoubleParameter, GroupState
from dynamic_reconfigure.srv import Reconfigure

# ROS1 compiles the messages into two, in contrast to ROS2.
from dynamic_reconfigure.srv import ReconfigureResponse

if autopsy.node.ROS_VERSION == 2:
# ROS2 uses different messages for rqt_reconfigure.
from rcl_interfaces.srv import SetParameters
from rcl_interfaces.msg import ParameterType, ParameterDescriptor, SetParametersResult, Parameter

# Translation of types to ParameterType
PTypes = {
bool: ParameterType.PARAMETER_BOOL,
int: ParameterType.PARAMETER_INTEGER,
float: ParameterType.PARAMETER_DOUBLE,
str: ParameterType.PARAMETER_STRING,
}


# https://stackoverflow.com/questions/2440692/formatting-floats-without-trailing-zeros
formatNumber = lambda x: ("%f" % x).rstrip("0").rstrip(".")
Expand Down Expand Up @@ -612,8 +625,8 @@ def __init__(self):
https://stackoverflow.com/questions/1132941/least-astonishment-and-the-mutable-default-argument
"""
self._parameters = ParameterDict()
self._description = ConfigDescription()
self._update = Config()
self._description = None
self._update = None
pass


Expand All @@ -624,6 +637,19 @@ def reconfigure(self, namespace = None, node = None):
else:
self._node = node

# ROS2: Use current Parameter API.
if autopsy.node.ROS_VERSION == 2:
self._node.add_on_set_parameters_callback(self._reconfigure2Callback)

self._redescribe2()

self._node.declare_parameters(
namespace = namespace,
parameters = self._description,
)

return

if namespace is None:
namespace = self._node.get_name()

Expand Down Expand Up @@ -736,6 +762,21 @@ def _redescribe(self):
)


def _redescribe2(self):
"""Creates a description of the parameters for ROS2."""

self._description = [
(
_name,
_param.default,
ParameterDescriptor(
type = PTypes[_param.type],
description = _param.description,
)
) for _name, _param in self._parameters.items()
]


def _reupdate(self):
"""Creates an update description of the parameters."""

Expand All @@ -754,6 +795,48 @@ def _reupdate(self):
self._update = _config


def _reconfigure2Callback(self, parameters):
"""Service callback for ROS2 dynamic reconfiguration.
Arguments:
parameters -- parameters to be set, list of Parameter
Returns:
result -- feedback whether the update was properly done, SetParametersResult
"""

for param in parameters:
_old_value = self._parameters[param.name].value

# Try to set the new value
try:
# a) Try to use the callback
if self._parameters[param.name].callback is not None:
# In ROS2 this could raise an Exception. If so, it is caught right away.
_new_value = self._parameters[param.name].callback(param.value)

# b) Check whether the value changed.
if _new_value != param.value:
self._parameters[param.name].callback(_old_value)
raise ValueError("Value of parameter '%s' changed after callback." % (param.name))

# c) Try to store the value
self._parameters[param.name].value = param.value

# d) Check whether the value changed.
if self._parameters[param.name].value != param.value:
self._parameters[param.name].value = _old_value
raise ValueError("Value of parameter '%s' changed to different value. Maybe the variable is linked?" % (param.name))

except Exception as e:
return SetParametersResult(
successful = False,
reason = str(e),
)

return SetParametersResult(successful = True)


def _reconfigureCallback(self, data, response = None):
"""Service callback for dynamic reconfiguration.
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autopsy</name>
<version>0.6.0</version>
<version>0.7.0</version>
<description>A set of Python utils for F1Tenth project.</description>

<maintainer email="[email protected]">Jaroslav Klapálek</maintainer>
Expand Down

0 comments on commit f6ebfc8

Please sign in to comment.