Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <ros/ros.h>
00033 #include <actionlib/client/simple_action_client.h>
00034 #include <actionlib/client/terminal_state.h>
00035
00036 #include <asctec_hl_comm/WaypointAction.h>
00037
00038 void feedbackCB(const asctec_hl_comm::WaypointFeedbackConstPtr & fb)
00039 {
00040 const geometry_msgs::Point32 & wp = fb->current_pos;
00041 ROS_INFO("got feedback: %fm %fm %fm %f° ", wp.x, wp.y, wp.z, fb->current_yaw*180/M_PI);
00042 }
00043
00044 void activeCb()
00045 {
00046 ROS_INFO("Goal just went active");
00047 }
00048
00049 void doneCb(const actionlib::SimpleClientGoalState& state, const asctec_hl_comm::WaypointResultConstPtr & result)
00050 {
00051 if (state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED)
00052 ROS_INFO("Finished in state [%s]", state.toString().c_str());
00053 else
00054 ROS_WARN("Finished in state [%s]", state.toString().c_str());
00055
00056 const geometry_msgs::Point32 & wp = result->result_pos;
00057 ROS_INFO("Reached waypoint: %fm %fm %fm %f°",wp.x, wp.y, wp.z, result->result_yaw*180/M_PI);
00058 }
00059
00060 int main(int argc, char** argv)
00061 {
00062
00063 ros::init(argc, argv, "waypoint_client");
00064 ros::NodeHandle nh;
00065
00066 float maxSpeed;
00067 float accuracy;
00068 ros::Duration timeout(15);
00069
00070 if (argc == 5)
00071 {
00072 maxSpeed = 0.5;
00073 accuracy = 0.3;
00074 }
00075 else if (argc == 6)
00076 {
00077 maxSpeed = atof(argv[5]);
00078 accuracy = 0.3;
00079 }
00080 else if (argc == 7)
00081 {
00082 maxSpeed = atof(argv[5]);
00083 accuracy = atof(argv[6]);
00084 }
00085 else if (argc == 8)
00086 {
00087 maxSpeed = atof(argv[5]);
00088 accuracy = atof(argv[6]);
00089 timeout = ros::Duration(atof(argv[7]));
00090 }
00091 else
00092 {
00093 std::cout << "Wrong number of arguments! \nusage:" << "\twpclient x y z yaw \n"
00094 << "\twpclient x y z yaw max_speed\n" << "\twpclient x y z yaw max_speed accuracy\n"
00095 << "\twpclient x y z yaw max_speed accuracy timeout\n" << std::endl;
00096 return -1;
00097 }
00098
00099 actionlib::SimpleActionClient<asctec_hl_comm::WaypointAction> ac(nh, "fcu/waypoint", true);
00100
00101 asctec_hl_comm::WaypointGoal goal;
00102
00103 ROS_INFO("Waiting for action server to start.");
00104 ac.waitForServer();
00105 ROS_INFO("Action server started, sending goal.");
00106
00107 goal.goal_pos.x = atof(argv[1]);
00108 goal.goal_pos.y = atof(argv[2]);
00109 goal.goal_pos.z = atof(argv[3]);
00110
00111 goal.max_speed.x = maxSpeed;
00112 goal.max_speed.y = maxSpeed;
00113 goal.max_speed.z = maxSpeed;
00114
00115 goal.goal_yaw = atof(argv[4]);
00116
00117 goal.accuracy_position = accuracy;
00118 goal.accuracy_orientation = 0;
00119
00120 goal.timeout = timeout.toSec();
00121
00122 ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCB);
00123
00124
00125 bool finished_before_timeout = ac.waitForResult(timeout);
00126
00127 if (!finished_before_timeout)
00128 {
00129 ROS_WARN("Action did not finish before the time out.");
00130 }
00131
00132 return 0;
00133 }