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 <string.h>
00033 #include <stdio.h>
00034 #include <math.h>
00035
00036 #include <ros/ros.h>
00037 #include <asctec_hl_comm/mav_ctrl.h>
00038 #include <asctec_hl_comm/mav_ctrl_motors.h>
00039
00040 void usage()
00041 {
00042 std::string text("usage: \n\n");
00043 text = "ctrl_test motors [0 | 1]\n";
00044 text += "ctrl_test ctrl [acc | vel | pos | vel_b | pos_b] x y z yaw\n";
00045 text += "position / velocity in [m] / [m/s] and yaw in [deg] / [deg/s] (-180 ... 180)\n";
00046 std::cout << text << std::endl;
00047 }
00048
00049 int main(int argc, char ** argv)
00050 {
00051
00052 ros::init(argc, argv, "interfacetest");
00053 ros::NodeHandle nh;
00054
00055 ros::Publisher pub;
00056
00057 if (argc == 1)
00058 {
00059 ROS_ERROR("Wrong number of arguments!!!");
00060 usage();
00061 return -1;
00062 }
00063
00064 std::string command = std::string(argv[1]);
00065
00066 if (command == "motors")
00067 {
00068 if (argc != 3)
00069 {
00070 ROS_ERROR("Wrong number of arguments!!!");
00071 usage();
00072 return -1;
00073 }
00074
00075 asctec_hl_comm::mav_ctrl_motors::Request req;
00076 asctec_hl_comm::mav_ctrl_motors::Response res;
00077 req.startMotors = atoi(argv[2]);
00078 ros::service::call("fcu/motor_control", req, res);
00079 std::cout << "motors running: " << (int)res.motorsRunning << std::endl;
00080 }
00081 else if (command == "ctrl")
00082 {
00083 if (argc != 7)
00084 {
00085 ROS_ERROR("Wrong number of arguments!");
00086 usage();
00087 return -1;
00088 }
00089 asctec_hl_comm::mav_ctrl msg;
00090 msg.x = atof(argv[3]);
00091 msg.y = atof(argv[4]);
00092 msg.z = atof(argv[5]);
00093 msg.yaw = atof(argv[6]) * M_PI / 180.0;
00094 msg.v_max_xy = -1;
00095 msg.v_max_z = -1;
00096
00097 std::string type(argv[2]);
00098 if (type == "acc")
00099 msg.type = asctec_hl_comm::mav_ctrl::acceleration;
00100 else if (type == "vel")
00101 msg.type = asctec_hl_comm::mav_ctrl::velocity;
00102 else if (type == "pos")
00103 msg.type = asctec_hl_comm::mav_ctrl::position;
00104 else if (type == "vel_b")
00105 msg.type = asctec_hl_comm::mav_ctrl::velocity_body;
00106 else if (type == "pos_b")
00107 msg.type = asctec_hl_comm::mav_ctrl::position_body;
00108 else
00109 {
00110 ROS_ERROR("Command type not recognized");
00111 usage();
00112 return -1;
00113 }
00114
00115 pub = nh.advertise<asctec_hl_comm::mav_ctrl> ("fcu/control", 1);
00116 ros::Rate r(15);
00117
00118 for (int i = 0; i < 15; i++)
00119 {
00120 pub.publish(msg);
00121 if (!ros::ok())
00122 return 0;
00123 r.sleep();
00124 }
00125
00126
00127 if (type != "pos" && type != "pos_b")
00128 {
00129 msg.x = 0;
00130 msg.y = 0;
00131 msg.z = 0;
00132 msg.yaw = 0;
00133 }
00134
00135 for(int i=0; i<5; i++){
00136 pub.publish(msg);
00137 r.sleep();
00138 }
00139
00140 ros::spinOnce();
00141 }
00142
00143 return 0;
00144 }