ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

ROS2 - rclpy set parameter example? [closed]

asked 2018-11-14 18:31:17 -0500

mkhansen gravatar image

Is there an example of setting parameters on another node using rclpy? I can't find one.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by mkhansen
close date 2020-02-28 16:15:22.756945

1 Answer

Sort by ยป oldest newest most voted
4

answered 2018-11-15 08:37:11 -0500

lucasw gravatar image

There may be additional helper functions or an entire wrapper but in bouncy I go through the set_parameters service interface.

class MinimalClientAsync(Node):

    def __init__(self):
        super().__init__('minimal_client_async')
        self.cli = self.create_client(SetParameters, 'v4l2ucp/set_parameters')
        while not self.cli.wait_for_service(timeout_sec=1.0):
            self.get_logger().info('service not available, waiting again...')
        self.req = None

    def send_request(self):
        self.req = SetParameters.Request()

        param = Parameter()
        param.name = "controls/Brightness"
        param.value.type = ParameterType.PARAMETER_INTEGER
        param.value.integer_value = 20
        self.req.parameters.append(param)

        param = Parameter()
        param.name = "controls/Contrast"
        param.value.type = ParameterType.PARAMETER_INTEGER
        param.value.integer_value = 15
        self.req.parameters.append(param)

        self.future = self.cli.call_async(self.req)

def main(args=None):
    rclpy.init(args=args)

    minimal_client = MinimalClientAsync()
    minimal_client.send_request()

    while rclpy.ok():
        rclpy.spin_once(minimal_client)
        if minimal_client.future.done():
            if minimal_client.future.result() is not None:
                response = minimal_client.future.result()
                minimal_client.get_logger().info(
                    'Result of set parameters: for %s' %
                    (str(response)))
            else:
                minimal_client.get_logger().info(
                    'Service call failed %r' % (minimal_client.future.exception(),))
            break

    minimal_client.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

https://github.com/lucasw/v4l2ucp/blo...

Adapted from https://github.com/ros2/examples/blob...

edit flag offensive delete link more

Comments

@lucasw - thanks I will try this and post back later

mkhansen gravatar image mkhansen  ( 2018-11-27 08:23:17 -0500 )edit

Works great in Dashing! Thx for the example.

clyde gravatar image clyde  ( 2019-10-31 21:22:59 -0500 )edit

This worked, sorry I should have closed it before, closing now with accepted answer.

mkhansen gravatar image mkhansen  ( 2020-02-28 16:14:52 -0500 )edit

Question Tools

Stats

Asked: 2018-11-14 18:31:17 -0500

Seen: 1,881 times

Last updated: Nov 15 '18