一、Action通信简介
三者区别:
话题通信:单向通信,发布后需要订阅 服务通信:请求一次任务,响应一次状态信息 Action通信:导航过程中连续反馈状态信息,导航终止时再返回执行结果
Action(动作)通信:基于功能包集actionlib实现通信
通信工作机制: 例如: Rviz中用2D Nav Goal发送一个目标点,请求了一个action,机器人收到这个action后,开始导航,导航过程当中会在终端连续收到运动状态等反馈信息,这样就实现了action通信;
可以使用的通信接口: (1)goal:发布任务目标; (2)cancel:请求取消任务; (3)status:通知Client当前的状态; (4)feedback:周期反馈任务运行的监控数据; (5)result:向Client发送任务的执行结果,只发布一次。
其中整个运动完成过程(导航过程)是基于move_base框架实现的
http://wiki.ros.org/move_base
二、案例1:单目标点导航
需求: 写一个客户端节点,来请求服务端做一件事,就是导航到某个目标点,你就要把目标点的坐标信息告诉它,它收到你的请求后会控制机器人移动,导航过程中还可以不断反馈给你机器人状态信息,整个通信方式就是Action通信。
按以下步骤来:
0、安装相关源码、依赖
sudo apt-get install ros-move-base-msgs
sudo apt-get install ros-noetic-dwa-local-planner
sudo apt-get install ros-noetic-gmapping
仿真环境:
git clone https://github.com/tianbot/tianbot_mini
git clone https://github.com/tianbot/tianbot_mini_description
git clone https://github.com/tianbot/tianbot_mini_gazebo
添加库
1、写好simple_goal.py节点,并添加为可执行文件(代码在最后)
2、加载仿真环境
roslaunch tianbot_mini_gazebo simulation.launch
3、启动SLAM
roslaunch tianbot_mini slam.launch
我习惯用: roscd ros_code/action python3 simple_goal.py 4、运行simple_goal.py节点
rosrun ros_code simple_goal.py
三、simple_goal.py
import roslib
import rospy
import actionlib
from actionlib_msgs.msg import *
from geometry_msgs.msg import Pose, PoseWithCovarianceStamped, Point, Quaternion, Twist
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
def client():
rospy.init_node('simple_goal', anonymous=True)
move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
move_base.wait_for_server(rospy.Duration(5.0))
rospy.loginfo("Connected to move base server")
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = 'map'
goal.target_pose.header.stamp = rospy.Time.now()
goal.target_pose.pose.position.x = 2.0
goal.target_pose.pose.orientation.w = 1.0
rospy.loginfo("Sending goal")
move_base.send_goal(goal)
finished_within_time = move_base.wait_for_result(rospy.Duration(300))
if not finished_within_time:
move_base.cancel_goal()
rospy.loginfo("Timed out achieving goal")
else:
state = move_base.get_state()
if state == GoalStatus.SUCCEEDED:
rospy.loginfo("Goal succeeded!")
else:
rospy.loginfo("Goal failed! ")
if __name__ == '__main__':
client()
参考:http://wiki.ros.org/move_base
|