第一步:定义请求反馈的变量
主要参考官网网站:Writing an action server and client (C++) — ROS 2 Documentation: Rolling documentation
与ros1的对比(74条消息) ROS入门之——action_沐棋的博客-CSDN博客_ros中action
在编写自己的actiion service和client之前,需要先定义自己的action动作类型,这一点和ros1是一样的。参考:Creating an action — ROS 2 Documentation: Rolling documentation
1.创建工作空间,创建代码包
mkdir -p ros2_ws/src #you can reuse existing workspace with this naming convention cd ros2_ws/src ros2 pkg create action_tutorials_interfaces
2.在action_tutorails_interface包中创建一个action文件夹, 并在该文件夹下新建一个脚本,该脚本为发送请求的类型
cd action_tutorials_interfaces
mkdir actiontouch Fibonacci.action
3.在这个Fibonacci.action文件中添加如下内容,order为请求时发送的变量,sequence为执行结果,partial_sequence为action执行过程中的反馈结果
int32 order
---
int32[] sequence
---
int32[] partial_sequence
4.在action_tutorails_interface文件夹下的CMakeLists.txt文件中添加如下内容,添加在ament_package()语句之前。该段代码会根据我们定义的请求类型Fibonacci在在/opt/ros/foxy/lib/python3.8/site-packages文件夹下生成action_tutorails_interface/action/_fibonacci.py等的文件。
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"action/Fibonacci.action"
)
5.在package.xml文件中添加如下内容
<buildtool_depend>rosidl_default_generators</buildtool_depend> <member_of_group>rosidl_interface_packages</member_of_group>
6.编译运行
cd ~/ros2_ws colcon build
至此,我们已经在环境变量中申明了请求的变量类型。
source一下 环境变量 . install/setup.bash,执行如下命令就能查看我们自己定义的请求类型了。
ros2 interface show action_tutorials_interfaces/action/Fibonaccis
输出如下:
第二步:编写action service的服务
1.在 action_tutorails_interface/src文件夹下新建脚本fibonacci_action_server.py
import time
import rclpy
from rclpy.action import ActionServer
from rclpy.node import Node
from action_tutorials_interfaces.action import Fibonacci
class FibonacciActionServer(Node):
def __init__(self):
super().__init__('fibonacci_action_server') #初始话节点名字,action service和client 根据这个节点名字和话题fibonacci通信
self._action_server = ActionServer(
self,
Fibonacci, #自己定义的消息类型
'fibonacci', #话题
self.execute_callback) #当这个类class:`ServerGoalHandle.execute()被执行的时候,execute_callback将被执行,
def execute_callback(self, goal_handle): #设置目标句柄(goal_handle)当类ServerGoalHandle构造的时候,goal_handle被赋值
self.get_logger().info('Executing goal...')
feedback_msg = Fibonacci.Feedback()
feedback_msg.partial_sequence = [0, 1]
for i in range(1, goal_handle.request.order): #执行斐波那契数列
feedback_msg.partial_sequence.append(
feedback_msg.partial_sequence[i] + feedback_msg.partial_sequence[i-1])
self.get_logger().info('Feedback: {0}'.format(feedback_msg.partial_sequence))
goal_handle.publish_feedback(feedback_msg)#只有在这里发布发聩结果,我们才可以在client里的send_goal_async(goal_msg, feedback_callback=self.feedback_callback) 的形参里有回调
time.sleep(1)
goal_handle.succeed() #使用目标句柄的方法succeed()来表示目标成功了
result = Fibonacci.Result()
result.sequence = feedback_msg.partial_sequence
return result
def main(args=None):
rclpy.init(args=args)
fibonacci_action_server = FibonacciActionServer()
rclpy.spin(fibonacci_action_server)
if __name__ == '__main__':
main()
2.在 action_tutorails_interface/src文件夹下新建脚本fibonacci_action_client.py,起始在哪里新建都行
import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from action_tutorials_interfaces.action import Fibonacci
class FibonacciActionClient(Node):
def __init__(self):
super().__init__('fibonacci_action_client')
self._action_client = ActionClient(self, Fibonacci, 'fibonacci')
def send_goal(self, order):
goal_msg = Fibonacci.Goal()
goal_msg.order = order
self._action_client.wait_for_server()
self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback) #本类的self.feedback_callback作为实参
self._send_goal_future.add_done_callback(self.goal_response_callback)
def goal_response_callback(self, future):
goal_handle = future.result()
if not goal_handle.accepted:
self.get_logger().info('Goal rejected :(')
return
self.get_logger().info('Goal accepted :)')
self._get_result_future = goal_handle.get_result_async()
self._get_result_future.add_done_callback(self.get_result_callback)
def get_result_callback(self, future):
result = future.result().result
self.get_logger().info('Result: {0}'.format(result.sequence))
rclpy.shutdown()
def feedback_callback(self, feedback_msg):
feedback = feedback_msg.feedback
self.get_logger().info('Received feedback: {0}'.format(feedback.partial_sequence))
def main(args=None):
rclpy.init(args=args)
action_client = FibonacciActionClient()
action_client.send_goal(10)
rclpy.spin(action_client)
if __name__ == '__main__':
main()
开启两个终端,在脚本所在的目录执行
一个终端执行
python3 fibonacci_action_server.py
另一个终端执行
python3 fibonacci_action_client.py
执行结果: