Action示例代码
- TaskAction.msg
- action_client.cpp
- action_server.cpp
- CMakeLists.txt
- 代码说明
- 使用方法
TaskAction.msg
# 目标消息(客户端发送给服务器)
uint64 task_id # 任务ID
string task_name # 任务名称
float32 target_value # 任务目标值
---
# 结果消息(服务器完成后返回)
uint64 task_id # 对应的任务ID
bool success # 是否成功
string message # 结果描述
float32 final_value # 最终结果值
---
# 反馈消息(服务器执行中实时发送)
uint64 task_id # 对应的任务ID
float32 progress # 任务进度(0.0-1.0)
string status # 当前状态描述
action_client.cpp
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include "your_package_name/TaskAction.h"
usingnamespace your_package_name;
// 动作完成回调函数
void doneCb(const actionlib::SimpleClientGoalState& state,
const TaskResultConstPtr& result) {
ROS_INFO("Task completed with state: %s", state.toString().c_str());
ROS_INFO("Result - ID: %ld, Success: %s, Message: %s, Value: %.2f",
result->task_id,
result->success ? "true" : "false",
result->message.c_str(),
result->final_value);
}
// 目标激活回调函数
void activeCb() {
ROS_INFO("Goal has been activated");
}
// 反馈回调函数
void feedbackCb(const TaskFeedbackConstPtr& feedback) {
ROS_INFO("Feedback - ID: %ld, Progress: %.0f%%, Status: %s",
feedback->task_id,
feedback->progress * 100,
feedback->status.c_str());
}
int main(int argc, char**argv) {
ros::init(argc, argv, "task_action_client");
// 创建Action客户端,连接到名为"task_action"的服务器
actionlib::SimpleActionClient<TaskAction> ac("task_action", true);
ROS_INFO("Waiting for action server to start...");
ac.waitForServer(); // 等待服务器启动
ROS_INFO("Action server connected");
// 创建目标消息
TaskGoal goal;
goal.task_id = 1001;
goal.task_name = "sample_task";
goal.target_value = 95.5;
// 发送目标并设置回调函数
ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); // 客户端将 goal 参数传递给 服务端占位符 _1
// 等待结果(最多等待30秒)
bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
if (finished_before_timeout) {
actionlib::SimpleClientGoalState state = ac.getState();
ROS_INFO("Task finished: %s", state.toString().c_str());
} else {
ROS_INFO("Task did not finish before timeout");
}
return0;
}
action_server.cpp
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include "your_package_name/TaskAction.h"
usingnamespace your_package_name;
class TaskActionServer {
private:
ros::NodeHandle nh_;
actionlib::SimpleActionServer<TaskAction> as_;
std::string action_name_;
// 反馈和结果消息
TaskFeedback feedback_;
TaskResult result_;
public:
// 构造函数:初始化Action服务器
TaskActionServer(std::string name) :
as_(nh_, name, boost::bind(&TaskActionServer::executeCB, this, _1), false),
action_name_(name) {
as_.start();
ROS_INFO("Action server [%s] started", action_name_.c_str());
}
~TaskActionServer(void) {}
// 执行回调函数:处理接收到的目标
void executeCB(const TaskGoalConstPtr &goal) {
ros::Rate r(10); // 10Hz循环
bool success = true;
// 初始化反馈信息
feedback_.task_id = goal->task_id;
feedback_.progress = 0.0;
feedback_.status = "Starting task";
ROS_INFO("Received task: ID=%ld, Name=%s, Target=%.2f",
goal->task_id, goal->task_name.c_str(), goal->target_value);
// 模拟任务执行过程
for (int i = 0; i <= 10; ++i) {
// 检查是否有取消请求
if (as_.isPreemptRequested() || !ros::ok()) {
ROS_INFO("Task [%ld] preempted", goal->task_id);
result_.success = false;
result_.message = "Task preempted";
as_.setPreempted(result_);
success = false;
break;
}
// 更新进度
feedback_.progress = i * 0.1; // 0.0 to 1.0
feedback_.status = "Executing task (" + std::to_string((int)(feedback_.progress*100)) + "%)";
as_.publishFeedback(feedback_);
r.sleep();
}
// 任务完成处理
if (success) {
result_.task_id = goal->task_id;
result_.success = true;
result_.message = "Task completed successfully";
result_.final_value = goal->target_value * 0.95; // 模拟计算结果
ROS_INFO("Task [%ld] completed: %s", goal->task_id, result_.message.c_str());
as_.setSucceeded(result_);
}
}
};
int main(int argc, char**argv) {
ros::init(argc, argv, "task_action_server");
// 创建Action服务器实例,Action名称为"task_action"
TaskActionServer server("task_action");
ros::spin();
return0;
}
CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS
roscpp
actionlib
actionlib_msgs
message_generation
)
# 生成Action消息
add_action_files(
FILES
TaskAction.msg
)
generate_messages(
DEPENDENCIES
actionlib_msgs
std_msgs
)
catkin_package(
CATKIN_DEPENDS roscpp actionlib actionlib_msgs message_runtime
)
# 编译服务器和客户端
include_directories(
${catkin_INCLUDE_DIRS}
)
add_executable(task_action_server src/action_server.cpp)
target_link_libraries(task_action_server ${catkin_LIBRARIES})
add_dependencies(task_action_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_executable(task_action_client src/action_client.cpp)
target_link_libraries(task_action_client ${catkin_LIBRARIES})
add_dependencies(task_action_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
代码说明
-
Action 消息定义(TaskAction.msg) -
包含三个部分:目标 (Goal)、结果 (Result) 和反馈 (Feedback) -
目标:客户端发送给服务器的任务参数 -
结果:服务器完成任务后返回的最终信息 -
反馈:服务器执行过程中发送的实时状态 -
Action 服务器(action_server.cpp) -
使用 SimpleActionServer实现,通过回调函数处理目标 -
主要功能:接收任务目标、执行任务、发送实时反馈、返回最终结果 -
支持任务取消功能(preempt) -
Action 客户端(action_client.cpp) -
使用 SimpleActionClient实现,用于发送任务请求 -
包含三个回调函数:处理完成结果、处理目标激活、处理实时反馈 -
支持等待任务完成和超时处理 -
CMake 配置 -
需要添加 actionlib和actionlib_msgs依赖 -
使用 add_action_files和generate_messages生成 Action 相关代码
使用方法
-
将上述文件放入 ROS 功能包中
-
替换
your_package_name为功能包名称 -
根据需求修改
TaskAction.msg中的消息字段 -
在服务器的
executeCB中实现实际任务逻辑 -
编译并运行:
catkin_make
rosrun your_package_name task_action_server
rosrun your_package_name task_action_client
这个模板可以作为 ROS Action 通信的基础框架,适用于需要双向通信、进度反馈和任务取消功能的场景,如机器人导航、机械臂控制等复杂任务。

