Skip to content

Commit

Permalink
make _on_parameter_event return result correctly (#817)
Browse files Browse the repository at this point in the history
* make _on_parameter_event return result correctly

Previously, `_on_parameter_event` always returned `successful=True` to the
caller (e.g., ros2param set) regardless of whether setting `use_sim_time`
parameter actually succeeded or not.

* PoC:
```sh
# terminal 1
$ ros2 run examples_rclpy_minimal_publisher publisher_member_function

[INFO] [1629490410.452032755] [minimal_publisher]: Publishing: "Hello World: 0"
[INFO] [1629490410.918999697] [minimal_publisher]: Publishing: "Hello World: 1"
[INFO] [1629490411.419087028] [minimal_publisher]: Publishing: "Hello World: 2"
[INFO] [1629490411.919343319] [minimal_publisher]: Publishing: "Hello World: 3"
[INFO] [1629490412.419345165] [minimal_publisher]: Publishing: "Hello World: 4"
[INFO] [1629490412.919260702] [minimal_publisher]: Publishing: "Hello World: 5"
[ERROR] [1629490413.030775970] [minimal_publisher]: use_sim_time parameter set to something besides a bool
[INFO] [1629490413.419389164] [minimal_publisher]: Publishing: "Hello World: 6"
[INFO] [1629490413.919106545] [minimal_publisher]: Publishing: "Hello World: 7"
```

```sh
# terminal 2
$ ros2 param set /minimal_publisher use_sim_time Trueeeee

Set parameter successful
```

As demonstrated above, when trying to set `use_sim_time` param to an invalid
type, the minimal_publisher node complains it cannot. However, ros2 param
prints "Set parameter successful". This commit fixes this issue.

Signed-off-by: Seulbae Kim <squizz617@gmail.com>

* use single quote

Signed-off-by: Seulbae Kim <squizz617@gmail.com>

Co-authored-by: Shane Loretz <sloretz@osrfoundation.org>
  • Loading branch information
squizz617 and sloretz authored Jul 18, 2022
1 parent 649bdec commit c4cf7a0
Showing 1 changed file with 9 additions and 4 deletions.
13 changes: 9 additions & 4 deletions rclpy/rclpy/time_source.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,19 +123,24 @@ def clock_callback(self, msg):
clock.set_ros_time_override(time_from_msg)

def _on_parameter_event(self, parameter_list):
successful = True
reason = ''

for parameter in parameter_list:
if parameter.name == USE_SIM_TIME_NAME:
if parameter.type_ == Parameter.Type.BOOL:
self.ros_time_is_active = parameter.value
else:
successful = False
reason = '{} parameter set to something besides a bool'.format(
USE_SIM_TIME_NAME)

node = self._get_node()
if node:
node.get_logger().error(
'{} parameter set to something besides a bool'
.format(USE_SIM_TIME_NAME))
node.get_logger().error(reason)
break

return SetParametersResult(successful=True)
return SetParametersResult(successful=successful, reason=reason)

def _get_node(self):
if self._node_weak_ref is not None:
Expand Down

0 comments on commit c4cf7a0

Please sign in to comment.