Created
August 1, 2013 15:58
-
-
Save mintar/6132716 to your computer and use it in GitHub Desktop.
actionlib_cpp_disconnect (see http://answers.ros.org/question/70012/actionlib-reconnect-problem-c-with-test-case/)
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#include <boost/thread.hpp> | |
#include <ros/ros.h> | |
#include <actionlib/client/action_client.h> | |
#include <actionlib/client/simple_action_client.h> | |
#include <actionlib/TestAction.h> | |
void ros_spin() | |
{ | |
ros::spin(); | |
} | |
int main(int argc, char** argv) | |
{ | |
ros::init(argc, argv, "client"); | |
ros::NodeHandle nh; | |
actionlib::SimpleActionClient<actionlib::TestAction> client("action", true); | |
client.waitForServer(); | |
int32_t counter = 0; | |
ros::Rate loop_rate(1.0); | |
while (ros::ok()) | |
{ | |
actionlib::TestGoal goal; | |
goal.goal = counter; | |
if (client.isServerConnected()) | |
{ | |
printf("client connected, sending goal=%d!\n", goal.goal); | |
client.sendGoal(goal); | |
bool finished_within_time = client.waitForResult(ros::Duration(10.0)); | |
if (!finished_within_time) | |
{ | |
client.cancelGoal(); | |
ROS_WARN("Timed out achieving goal!"); | |
} | |
else | |
{ | |
actionlib::SimpleClientGoalState state = client.getState(); | |
if (state == actionlib::SimpleClientGoalState::SUCCEEDED) | |
ROS_INFO("Action finished: %s", state.toString().c_str()); | |
else | |
ROS_INFO("Action failed: %s", state.toString().c_str()); | |
} | |
} | |
else | |
{ | |
printf("client not connected, skipping goal=%d!\n", goal.goal); | |
// client.cancelAllGoals(); | |
} | |
loop_rate.sleep(); | |
ros::spinOnce(); | |
counter++; | |
} | |
return 0; | |
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#include <ros/ros.h> | |
#include <actionlib/server/action_server.h> | |
#include <actionlib/server/simple_action_server.h> | |
#include <actionlib/TestAction.h> | |
actionlib::SimpleActionServer<actionlib::TestAction>* server = 0; | |
void cb_goal(const actionlib::SimpleActionServer<actionlib::TestAction>::GoalConstPtr &goal) | |
{ | |
printf("server received new goal, goal=%d!\n", goal->goal); | |
server->setSucceeded(); | |
} | |
int main(int argc, char **argv) | |
{ | |
ros::init(argc, argv, "server"); | |
ros::NodeHandle nh; | |
server = new actionlib::SimpleActionServer<actionlib::TestAction>(nh, "action", cb_goal, false); | |
server->start(); | |
ros::spin(); | |
return 0; | |
} |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment