A Minimal Action Client
The Code¶
Review the code (including the annotations) and then take a copy of it.
#! /usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient # (1)!
from tuos_interfaces.action import CameraSweep # (2)!
class CameraSweepActionClient(Node):
def __init__(self):
super().__init__("camera_sweep_action_client") # (3)!
self.actionclient = ActionClient(
node=self,
action_type=CameraSweep,
action_name="camera_sweep"
) # (4)!
self.declare_parameters(
namespace='',
parameters=[
('goal_images', 0),
('goal_angle', 0)
]
) # (5)!
def send_goal(self): # (6)!
images = self.get_parameter(
'goal_images'
).get_parameter_value().integer_value
angle = self.get_parameter(
'goal_angle'
).get_parameter_value().integer_value
goal = CameraSweep.Goal() # (7)!
goal.sweep_angle = float(angle)
goal.image_count = images
self.actionclient.wait_for_server() # (8)!
# send the goal to the action server:
return self.actionclient.send_goal_async(goal)
def main(args=None): # (9)!
rclpy.init(args=args)
action_client = CameraSweepActionClient()
future = action_client.send_goal()
rclpy.spin_until_future_complete(action_client, future)
if __name__ == '__main__':
main()
-
As you know by now, in order to develop ROS nodes using Python we need to import the
rclpyclient library, and theNodeclass to base our node upon. In addition, here we're also importing anActionClientclass too. -
We know that the
/camera_sweepAction server uses theCameraSweepactioninterface from thetuos_interfacespackage, so we import that here too (which we use to make a call to the server). -
Standard practice when we initialise ROS nodes: we must give them a name
-
Here, we instantiate an
ActionClientclass object. In doing this we define thenodeto add the action client too (in our caseself, i.e. ourCameraSweepActionClientclass). We then also define the interface type used by the server (CameraSweep), and the name of the action that we want to call (action_name="camera_sweep"). -
Here we're declaring two ROS parameters:
goal_imagesandgoal_angle.We'll use these to set goals for the action server at runtime.
By default, these values are set to
0, so if we don't explicitly set values for these two parameters then they will remain at0!Question
How do we set values for parameters at runtime (i.e. when we execute this node using
ros2 run)? -
Here we define a class method to construct and deliver a goal to the server.
-
As we know from earlier, a
CameraSweep.Goal()contains two parameters that we can assign values to:sweep_angleandimage_count.As above, the values assigned to these are derived from two ROS parameters:
goal_angleandgoal_images.Remember
By default, both parameters will have a value of
0unless we explicitly assign a value to them (see above)!How do we assign values to these parameters at runtime? Recall how we did this in Part 4.
-
The goal is sent to the server using the
send_goal_async()method, which returns a future: i.e. something that will happen in the future, that we can wait on. This future is returned once the goal parameters have been accepted by the server, not when the action server has actually completed its job. -
In our
mainmethod we initialiserclpyand ourCameraSweepActionClientclass (nothing new here), but then we call thesend_goal()method of our class (as discussed above), which returns a future. We can then use therclpy.spin_until_future_complete()method to spin up our node only until this future object has finished.
Package Dependencies¶
The action client has two key dependencies, so we need to modify the package.xml file (below the <exec_depend>rclpy</exec_depend> line) to include these: