Skip to content

Commit

Permalink
Support multiple on parameter set callbacks
Browse files Browse the repository at this point in the history
Signed-off-by: Abhinav Singh <singhabhinav9051571833@gmail.com>
  • Loading branch information
dirk-thomas authored and suab321321 committed Nov 9, 2019
1 parent af632a4 commit 3a941ab
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 7 deletions.
2 changes: 1 addition & 1 deletion rclpy/rclpy/duration.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import builtin_interfaces
import builtin_interfaces.msg
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


Expand Down
31 changes: 26 additions & 5 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,8 @@ def __init__(
self.__guards: List[GuardCondition] = []
self.__waitables: List[Waitable] = []
self._default_callback_group = MutuallyExclusiveCallbackGroup()
self._parameters_callback: List[Callable[[List[Parameter]], SetParametersResult]] = []
self._rate_group = ReentrantCallbackGroup()
self._parameters_callback = None
self._allow_undeclared_parameters = allow_undeclared_parameters
self._parameter_overrides = {}
self._descriptors = {}
Expand Down Expand Up @@ -715,9 +715,11 @@ def _set_parameters_atomically(
if not result.successful:
return result
elif self._parameters_callback:
result = self._parameters_callback(parameter_list)
else:
result = SetParametersResult(successful=True)
for callback in self._parameters_callback:
result = callback(parameter_list)
if(not result.successful):
return result
result = SetParametersResult(successful=True)

if result.successful:
parameter_event = ParameterEvent()
Expand Down Expand Up @@ -761,6 +763,25 @@ def _set_parameters_atomically(

return result

def add_on_set_paramters_callback(
self,
callback: Callable[[List[Parameter]], SetParametersResult]
) -> None:
"""Add the callback to list."""
prevCallBack = self._parameters_callback
prevCallBack.insert(0, callback)
self._parameters_callback = prevCallBack

def remove_on_set_parameters_callback(
self,
callback: Callable[[List[Parameter]], SetParametersResult]
) -> None:
"""Remove callback from list."""
if callback in self._parameters_callback:
self._parameters_callback.remove(callback)
else:
print('Callback does not exist')

def _apply_descriptors(
self,
parameter_list: List[Parameter],
Expand Down Expand Up @@ -1019,7 +1040,7 @@ def set_parameters_callback(
"""
Register a set parameters callback.
Calling this function with override any previously registered callback.
Calling this function will override any previously registered callback.
:param callback: The function that is called whenever parameters are set for the node.
"""
Expand Down
2 changes: 1 addition & 1 deletion rclpy/rclpy/time.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import builtin_interfaces
import builtin_interfaces.msg
from rclpy.clock import ClockType
from rclpy.duration import Duration
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
Expand Down

0 comments on commit 3a941ab

Please sign in to comment.