Skip to content

Commit

Permalink
Merge branch 'release/0.6.0'
Browse files Browse the repository at this point in the history
  • Loading branch information
jara001 committed Aug 24, 2022
2 parents 5ac98fa + 04263b1 commit f095b26
Show file tree
Hide file tree
Showing 4 changed files with 122 additions and 11 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.6.0 - 2022-08-24
### Added
- `reconfigure`:
- Parameters can be now used within conditions.
- Implementation of `__contains__` to support `if ... in P`.
- `update()` now takes optional argument `only_existing` (def. `False`) to only update existing parameters.
- (ROS1 only) Parameters and their values are exposed to the ROS Parameter Server.
- `link(ConstrainedP, ConstrainedP)` to link two parameters together. First cannot be larger then the second one.

## 0.5.1 - 2022-03-23
### Added
- `reconfigure`:
Expand Down
21 changes: 20 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ Upon assigning a value to parameter, an internal object is created.

_Note: The `.value` is used only when you want to store it somewhere else._

_Note: Features `is`, `not` and `bool()` are not currently available here._
_Note: Feature `is` are not currently available here._

Example:
```python
Expand Down Expand Up @@ -185,6 +185,23 @@ P.reconfigure()
_Note: Callback function receives new value of the parameter, and is required to return the true new value. It is then filled inside the parameter and announced to the reconfigure GUI._


##### Linked variables

Parameters of type `ConstrainedP` can be "linked" together. When done, first parameter cannot exceed the value of the second parameter and vice versa. Linking is performed after defining the parameters using `P.link()`.

Example:
```python
P = ParameterServer()

P.range_min = 2.0
P.range_max = 3.0

P.link(P.range_min, P.range_max)

# P.range_min and P.range_max are now linked. Should min be over max, it is set to max, and vice versa.
```


#### Reconfiguration itself

```python
Expand All @@ -203,6 +220,8 @@ P.reconfigure()
```
_Note: Passing a string to `P.reconfigure()` changes the namespace of the ParameterServer in ROS._

_Note: From `>0.5.1` an additional bool can be passed to `P.update()` to only update existing parameters._


### Compatibility

Expand Down
101 changes: 92 additions & 9 deletions autopsy/reconfigure.py
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,10 @@ def __operator__(first, second = None, operator = None):
class ConstrainedP(Parameter):
"""Parameter that is constrained by min and max values."""

# Constrain the value even further by looking at a linked variable.
_link = None


def __init__(self, name, default, type, min = -2147483647, max = 2147483647, **kwargs):
"""Initialize a constrained parameter object.
Expand Down Expand Up @@ -451,6 +455,9 @@ def value(self, new_value):
if not self.min <= new_value <= self.max:
raise ValueError("Value '%s' is not in %s <= value <= %s range." % (formatNumber(new_value), formatNumber(self.min), formatNumber(self.max)))

if self._link is not None:
new_value = self._link(new_value)

Parameter.value.fset(self, new_value)


Expand All @@ -470,13 +477,31 @@ def __init__(self, name, default, *args, **kwargs):
super(IntP, self).__init__(name, default, int, *args, **kwargs)


def __nonzero__(self):
"""Used for evaluating conditions (Py2)."""
return self.value != 0

def __bool__(self):
"""Used for evaluating conditions (Py3)."""
return self.value != 0


class DoubleP(ConstrainedP):
"""Parameter of a type float/double."""

def __init__(self, name, default, *args, **kwargs):
super(DoubleP, self).__init__(name, default, float, *args, **kwargs)


def __nonzero__(self):
"""Used for evaluating conditions (Py2)."""
return self.value != 0.0

def __bool__(self):
"""Used for evaluating conditions (Py3)."""
return self.value != 0.0


class BoolP(Parameter):
"""Parameter of a type bool."""

Expand All @@ -487,6 +512,15 @@ def __init__(self, name, default, *args, **kwargs):
super(BoolP, self).__init__(name, default, bool, *args, **kwargs)


def __nonzero__(self):
"""Used for evaluating conditions (Py2)."""
return self.value

def __bool__(self):
"""Used for evaluating conditions (Py3)."""
return self.value


class StrP(Parameter):
"""Parameter of a type string."""

Expand All @@ -497,6 +531,11 @@ def __init__(self, name, default, *args, **kwargs):
super(StrP, self).__init__(name, default, str, *args, **kwargs)


def __len__(self):
"""Size of the string. Also used for evaluating conditions."""
return len(self.value)


######################
# ParameterDict
######################
Expand Down Expand Up @@ -559,6 +598,8 @@ class ParameterReconfigure(object):
_pub_description = None
_pub_update = None
_service = None
_node = None
_expose_parameters = False

def __init__(self):
"""Initialize variables of the object.
Expand All @@ -579,16 +620,24 @@ def __init__(self):
def reconfigure(self, namespace = None, node = None):

if node is None:
node = autopsy.node.rospy
self._node = autopsy.node.rospy
else:
self._node = node

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

self._pub_description = node.Publisher("%s/parameter_descriptions" % namespace,
self._pub_description = self._node.Publisher("%s/parameter_descriptions" % namespace,
ConfigDescription, queue_size = 1, latch = True)
self._pub_update = node.Publisher("%s/parameter_updates" % namespace,
self._pub_update = self._node.Publisher("%s/parameter_updates" % namespace,
Config, queue_size = 1, latch = True)
self._service = node.Service("%s/set_parameters" % namespace, Reconfigure, self._reconfigureCallback)
self._service = self._node.Service("%s/set_parameters" % namespace, Reconfigure, self._reconfigureCallback)

# Expose parameters to the ROS Parameter Server (ROS1 only)
if hasattr(self._node, "set_param"):
self._expose_parameters = True
for _name, _param in self._parameters.items():
self._node.set_param("~%s" % _name, _param.value)

self._redescribe()
self._describePub()
Expand Down Expand Up @@ -690,7 +739,9 @@ def _redescribe(self):
def _reupdate(self):
"""Creates an update description of the parameters."""

_config = self._get_config(condition = lambda x: x.value != x.default)
# Note: Condition was removed because of the linked variables, as when
# the value should be moved to its default state, nothing would happen.
_config = self._get_config()#condition = lambda x: x.value != x.default)
_config.groups = [
GroupState(
name = "Default",
Expand Down Expand Up @@ -722,6 +773,10 @@ def _reconfigureCallback(self, data, response = None):
else:
self._parameters[param.name].value = self._parameters[param.name].callback(param.value)

# Expose the update to the ROS Parameter Server (ROS1 only)
if self._expose_parameters:
self._node.set_param("~%s" % param.name, param.value)

_updated.append(param.name)


Expand Down Expand Up @@ -836,18 +891,46 @@ def __setattr__(self, name, value):
raise TypeError("Unable to create a parameter of type '%s'." % type(value))


def update(self, parameters):
def __contains__(self, name):
"""Check whether a parameter name exists. Used for 'if name in P'.
Arguments:
name -- name of the parameter, str
"""
return name in self._parameters


def link(self, param1, param2):
"""Links two constrained parameters together so one cannot be more then the other.
Arguments:
name1 -- name of the first ConstrainedP parameter, str
name2 -- name of the second ConstrainedP parameter, str
"""

for param in (param1, param2):
if not isinstance(param, ConstrainedP):
raise TypeError("Parameter '%s' is of a type '%s'." % (param.name, type(param)))

param1._link = lambda x: min(x, param2.value)
param2._link = lambda x: max(x, param1.value)


def update(self, parameters, only_existing = False):
"""Updates the parameters according to the passed dictionary.
Arguments:
parameters -- new values of the parameters, dict(str, any) or list(tuple(str, any))
only_existing -- when True only update values, do not add new parameters, bool, default False
"""

if isinstance(parameters, dict):
for param, value in parameters.items():
self.__setattr__(param, value)
if not only_existing or param in self:
self.__setattr__(param, value)
elif isinstance(parameters, list):
for param, value in parameters:
self.__setattr__(param, value)
if not only_existing or param in self:
self.__setattr__(param, value)
else:
raise NotImplementedError("ParameterServer.update() is not supported for type '%s'." % type(parameters))
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.5.1</version>
<version>0.6.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 f095b26

Please sign in to comment.