[ROS] Action 通信,ActionClient 创建
1. Action Client 完整代码
#include <iostream>
#include <ros/ros.h>
#include <actionlib/client/action_client.h>
#include <demo_action_msgs/CountNumberAction.h>
typedef actionlib::ClientGoalHandle <demo_action_msgs::CountNumberAction> GoalHandle;
typedef const demo_action_msgs::CountNumberFeedbackConstPtr FeedbackConstPtr;
typedef actionlib::ActionClient <demo_action_msgs::CountNumberAction> ActionClient;
void TransitionCallback(GoalHandle handle) {
ROS_INFO_STREAM("client: TransitionCallback");
const actionlib::CommState &commState = handle.getCommState();
if (commState == commState.ACTIVE) {
ROS_INFO_STREAM("state active.");
} else if (commState == commState.DONE) {
ROS_INFO_STREAM("state done.");
const actionlib::TerminalState &state = handle.getTerminalState();
if (state == state.SUCCEEDED) {
ROS_INFO_STREAM("SUCCEEDED.");
} else if(state == state.PREEMPTED) {
ROS_INFO_STREAM("PREEMPTED.");
} else if(state == state.ABORTED) {
ROS_INFO_STREAM("ABORTED.");
} else if(state == state.REJECTED) {
ROS_INFO_STREAM("REJECTED.");
}
}
}
void FeedbackCallback(GoalHandle handle, FeedbackConstPtr &feedback) {
ROS_INFO_STREAM("client: FeedbackCallback" << feedback->percent);
}
int main(int argc, char **argv) {
std::string nodeName = "cpp_action_client_node";
ros::init(argc, argv, nodeName);
ros::NodeHandle node;
ros::AsyncSpinner spinner(1);
spinner.start();
std::string actionName = "/hello/action";
ActionClient client(node, actionName);
client.waitForActionServerToStart();
demo_action_msgs::CountNumberGoal goal;
goal.max = 100;
goal.duration = 0.1;
const actionlib::ActionClient<demo_action_msgs::CountNumberAction>::GoalHandle &clientGoalHandle = client.sendGoal(
goal,
boost::bind(TransitionCallback, _1),
boost::bind(FeedbackCallback, _1, _2));
ros::waitForShutdown();
return 0;
}
2. 调试验证(与 Action Server 联调)(见 Action Server)
*. todo