find_package
中添加actionlib
和 actionlib_msgs
1 | add_action_files( |
package.xml
添加actionlib
的编译和执行依赖,如下:1
2
3
4<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<run_depend>actionlib</run_depend>
<run_depend>actionlib_msgs</run_depend>
服务端
1 | // action定义在 scheduler/action/Scheduler.action |
SimpleActionServer
有构造函数可以注册ExecuteCallback
回调函数,但没有其他两个回调,原型:SimpleActionServer (ros::NodeHandle n, std::string name, ExecuteCallback execute_callback, bool auto_start)
move_base
的构造函数中是这样使用的:as_ = new MoveBaseActionServer(ros::NodeHandle(), "move_base", boost::bind(&MoveBase::executeCb, this, _1), false);
服务端as_
最后需要start()
来启动,再加ros::spin()
阻塞。 MoveBase
构造函数的最后只有前者,ros::spin()
其实是在move_base_node.cpp
里
客户端
这里只看带回调函数的函数原型:1
2
3
4
5void actionlib::SimpleActionClient< ActionSpec >::sendGoal(const Goal& goal,
SimpleDoneCallback done_cb = SimpleDoneCallback(),
SimpleActiveCallback active_cb = SimpleActiveCallback(),
SimpleFeedbackCallback feedback_cb = SimpleFeedbackCallback()
)
向ActionServer
发送goal, 并注册回调函数。 如果调用本函数时已经有个goal处于active,状态机就会忽略goal并且开始向新的goal导航,不用发取消的请求。
- done_cb: Callback that gets called on transitions to
Done
,用于监听服务器任务执行完后的相应消息以及客户端的相应处理 - active_cb: Callback that gets called on transitions to
Active
,服务器任务被激活时的消息提示以及客户端的相应处理 - feedback_cb: Callback that gets called whenever
feedback
for this goal is received,接收服务器的反馈消息以及客户端的相应处理1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
MoveBaseClient ac_;
// 示例
ac_.sendGoal(goal,
boost::bind(&DoDishesActionClient::DoneCb, this, _1, _2),
boost::bind(&DoDishesActionClient::ActiveCb, this),
boost::bind(&DoDishesActionClient::FeedbackCb, this, _1));
void DoneCb(const actionlib::SimpleClientGoalState& state,
const first_actionlib_sample::DoDishesResultConstPtr& result)
{
ROS_INFO("Finished in state [%s]", state.toString().c_str());
ROS_INFO("Toal dish cleaned: %i", result->toal_dishes_cleaned);
ros::shutdown();
}
// 当目标激活的时候,会调用一次
void ActiveCb()
{
ROS_INFO("Goal just went active");
}
// 接收服务器的反馈信息
void FeedbackCb(const first_actionlib_sample::DoDishesFeedbackConstPtr& feedback) {
ROS_INFO("Got Feedback Complete Rate: %f", feedback->percent_complete);
}
Goal的状态
GoalStatus
1
2
3
4
5
6
7
8
9
10PENDING = 0
ACTIVE = 1
PREEMPTED = 2
SUCCEEDED = 3
ABORTED = 4
REJECTED = 5
PREEMPTING = 6
RECALLING = 7
RECALLED = 8
LOST = 9
1 | cout<< ac_.getState().toString() <<endl; |
如果当前已经在某个状态,再次设置为这个状态就会报警:比如ABORTED
状态 To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: 4