(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

ServiceState (ROS)

Description: 本教程展示如何将服务的执行表示为一个SMACH状态。

Tutorial Level: BEGINNER

Next Tutorial: 监视状态

   1 from smach_ros import ServiceState

你可以简单地从通用状态中调用任何服务,但是smach对调用服务有特定的支持,为你节省了大量代码,!SMACH提供一个状态类,它充当ROS服务的代理。状态的实例化采用服务名称、服务类型和生成服务请求的一些策略。服务状态的可能结果是'成功(succeeded)'、'抢占(preempted)'和'中止(aborted)'。

/!\ 服务状态与简单的动作状态几乎相同。用'request'代替'goal',用'response'代替'result'。

请求

空请求消息

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     smach.StateMachine.add('TRIGGER_GRIPPER',
   4                            ServiceState('service_name',
   5                                         GripperSrv),
   6                            transitions={'succeeded':'APPROACH_PLUG'})

固定请求消息

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     smach.StateMachine.add('TRIGGER_GRIPPER',
   4                            ServiceState('service_name',
   5                                         GripperSrv,
   6                                         request = GripperSrv(9.0)),
   7                            transitions={'succeeded':'APPROACH_PLUG'})

/!\ 你可能需要使用实际的请求类型而不是服务类型:ie。 request = GripperSrvRequest(9.0)替代GripperSrv

从用户数据请求

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     smach.StateMachine.add('TRIGGER_GRIPPER',
   4                            ServiceState('service_name',
   5                                         GripperSrv,
   6                                         request_slots = ['max_effort',
   7                                                          'position']),
   8                            transitions={'succeeded':'APPROACH_PLUG'})

请求回调

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3 
   4     @smach.cb_interface(input_keys=['gripper_input'])
   5     def gripper_request_cb(userdata, request):
   6        gripper_request = GripperSrv().Request
   7        gripper_request.position.x = 2.0
   8        gripper_request.max_effort = userdata.gripper_input
   9        return gripper_request
  10 
  11     smach.StateMachine.add('TRIGGER_GRIPPER',
  12                            ServiceState('service_name',
  13                                         GripperSrv,
  14                                         request_cb = gripper_request_cb,
  15                                         input_keys = ['gripper_input']),
  16                            transitions={'succeeded':'APPROACH_PLUG'})

关于更多高级回调使用方法,查看@smach.cb_interface.

响应

用户数据响应

响应回调

该步骤和SimpleActionState结果回调类似, 除了接收结果状态和结果数据之外,回调的第二个参数只是服务响应消息。

关于更多高级回调使用方法,查看@smach.cb_interface.

Wiki: cn/smach/Tutorials/ServiceState (last edited 2018-03-10 07:39:32 by Playfish)