ROS kinetic 动作编程

Action接口
goal    发布任务目标
cancel    请求取消任务
status    通知客户端当前的状态
feedback    周期反馈任务运行的监控数据

result    向客户端发送任务的执行结果,只发布一次

自定义动作消息
消息类型

定义action

kinetic@vm:~$ mkdir ~/catkin_ws/src/learning_communication/action
kinetic@vm:~$ cd ~/catkin_ws/src/learning_communication/action
kinetic@vm:~/catkin_ws/src/learning_communication/action$ cat DoDishes.action 
# 定义目标信息    goal
uint32 dishwasher_id
---
# 定义结果信息 result
uint32 total_dishes_cleaned
---
# 定义周期反馈的消息    feedback msg

float32 percent_complete

修改 ~/catkin_ws/src/learning_communication/package.xml
  <build_depend>actionlib</build_depend>
  <exec_depend>actionlib</exec_depend>
  <build_depend>actionlib_msgs</build_depend>

  <exec_depend>actionlib_msgs</exec_depend>

修改 ~/catkin_ws/src/learning_communication/CMakeLists.txt
find_package(catkin REQUIRED   actionlib_msgs  actionlib)
add_action_files( DIRECTORY  action  FILES  DoDishes.action )

generate_messages( DEPENDENCIES  std_msgs  actionlib_msgs )

编译

kinetic@vm:~/catkin_ws$ catkin_make

创建动作服务端 ~/catkin_ws/src/learning_communication/src/DoDishes_server.cpp

#include "ros/ros.h"
#include "actionlib/server/simple_action_server.h"
#include "learning_communication/DoDishesAction.h"

typedef actionlib::SimpleActionServer<learning_communication::DoDishesAction> Server;

// 收到action的goal后调用该回调函数
void execute(const learning_communication::DoDishesGoalConstPtr &goal, Server *as)
{
	ros::Rate r(1);
	learning_communication::DoDishesFeedback feedback;
	
	ROS_INFO("Dishwasher %d is working.", goal->dishwasher_id);
	
	// 假设洗盘子的进度,并且按照1Hz的频率发布进度feedback 
	for(int i = 1; i <= 10; i++)
	{
		feedback.percent_complete = i * 10;
		as->publishFeedback(feedback);
		r.sleep();
	}
	
	// 当action完成后,向客户端返回结果
	ROS_INFO("Dishwasher %d finish working.", goal->dishwasher_id);
	as->setSucceeded();
}

int main(int argc, char **argv)
{
	ros::init(argc, argv, "do_dishes_server");
	ros::NodeHandle hNode;
	
	// 定义一个服务器
	Server server(hNode, "do_dishes", boost::bind(&execute, _1, &server), false);
	
	// 服务器开始运行
	server.start();
	
	ros::spin();

	return 0;
}

创建动作客户端 ~/catkin_ws/src/learning_communication/src/DoDishes_client.cpp

#include "ros/ros.h"
#include "actionlib/client/simple_action_client.h"
#include "learning_communication/DoDishesAction.h"

typedef actionlib::SimpleActionClient<learning_communication::DoDishesAction> Client;

// 当action完成后会调用该回调函数一次
void doneCallback(const actionlib::SimpleClientGoalState &state
	, const learning_communication::DoDishesResultConstPtr &result)
{
	ROS_INFO("Yay! The dishes are now clean");
	ros::shutdown();
}

// 当action激活后会调用该回调函数一次
void activeCallback()
{
	ROS_INFO("Goal just went active");
}

// 收到feedback后调用该回调函数
void feedbackCallback(const learning_communication::DoDishesFeedbackConstPtr &feedback)
{
	ROS_INFO("percent_complete : %f", feedback->percent_complete);
}

int main(int argc, char **argv)
{
	ros::init(argc, argv, "do_dishes_client");
	
	// 定义一个客户端
	Client client("do_dishes", true);
	
	// 等待服务器端
	ROS_INFO("Waiting for action server to start.");
	client.waitForServer();
	ROS_INFO("Action server started, sending goal.");
	
	// 创建一个 action 的 goal
	learning_communication::DoDishesGoal goal;
	goal.dishwasher_id = 1;

	// 发送action的goal给服务端,并且设置回调函数
	client.sendGoal(goal, &doneCallback, &activeCallback, &feedbackCallback);

	ros::spin();
	
	return 0;
}

修改 ~/catkin_ws/src/learning_communication/CMakeLists.txt

add_executable(DoDishes_server src/DoDishes_server.cpp)

add_executable(DoDishes_client src/DoDishes_client.cpp)

target_link_libraries(DoDishes_server ${catkin_LIBRARIES})

target_link_libraries(DoDishes_client ${catkin_LIBRARIES})

add_dependencies(DoDishes_server ${PROJECT_NAME}_EXPORTED_TARGETS)

add_dependencies(DoDishes_client ${PROJECT_NAME}_EXPORTED_TARGETS)

编译
kinetic@vm:~/catkin_ws$ catkin_make

运行
kinetic@vm:~$ roscore
kinetic@vm:~$ rosrun learning_communication DoDishes_server
kinetic@vm:~$ rosrun learning_communication DoDishes_client

猜你喜欢

转载自blog.csdn.net/youshijian99/article/details/80027488