00001 /* 00002 00003 Copyright (c) 2011, Markus Achtelik, ASL, ETH Zurich, Switzerland 00004 You can contact the author at <markus dot achtelik at mavt dot ethz dot ch> 00005 00006 All rights reserved. 00007 00008 Redistribution and use in source and binary forms, with or without 00009 modification, are permitted provided that the following conditions are met: 00010 * Redistributions of source code must retain the above copyright 00011 notice, this list of conditions and the following disclaimer. 00012 * Redistributions in binary form must reproduce the above copyright 00013 notice, this list of conditions and the following disclaimer in the 00014 documentation and/or other materials provided with the distribution. 00015 * Neither the name of ETHZ-ASL nor the 00016 names of its contributors may be used to endorse or promote products 00017 derived from this software without specific prior written permission. 00018 00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY 00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 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] x y z yaw\n"; 00045 std::cout << text << std::endl; 00046 } 00047 00048 int main(int argc, char ** argv) 00049 { 00050 00051 ros::init(argc, argv, "interfacetest"); 00052 ros::NodeHandle nh; 00053 00054 ros::Publisher pub; 00055 00056 if (argc == 1) 00057 { 00058 ROS_ERROR("Wrong number of arguments!!!"); 00059 usage(); 00060 return -1; 00061 } 00062 00063 std::string command = std::string(argv[1]); 00064 00065 if (command == "motors") 00066 { 00067 if (argc != 3) 00068 { 00069 ROS_ERROR("Wrong number of arguments!!!"); 00070 usage(); 00071 return -1; 00072 } 00073 00074 asctec_hl_comm::mav_ctrl_motors::Request req; 00075 asctec_hl_comm::mav_ctrl_motors::Response res; 00076 req.startMotors = atoi(argv[2]); 00077 ros::service::call("fcu/motor_control", req, res); 00078 std::cout << "motors running: " << (int)res.motorsRunning << std::endl; 00079 } 00080 else if (command == "ctrl") 00081 { 00082 if (argc != 7) 00083 { 00084 ROS_ERROR("Wrong number of arguments!"); 00085 usage(); 00086 return -1; 00087 } 00088 asctec_hl_comm::mav_ctrl msg; 00089 msg.x = atof(argv[3]); 00090 msg.y = atof(argv[4]); 00091 msg.z = atof(argv[5]); 00092 msg.yaw = atof(argv[6]); 00093 msg.v_max_xy = -1; // use max velocity from config 00094 msg.v_max_z = -1; 00095 00096 std::string type(argv[2]); 00097 if (type == "acc") 00098 msg.type = asctec_hl_comm::mav_ctrl::acceleration; 00099 else if (type == "vel") 00100 msg.type = asctec_hl_comm::mav_ctrl::velocity; 00101 else if (type == "pos") 00102 msg.type = asctec_hl_comm::mav_ctrl::position; 00103 else 00104 { 00105 ROS_ERROR("Command type not recognized"); 00106 usage(); 00107 return -1; 00108 } 00109 00110 pub = nh.advertise<asctec_hl_comm::mav_ctrl> ("fcu/control", 1); 00111 ros::Rate r(15); // ~15 Hz 00112 00113 for (int i = 0; i < 15; i++) 00114 { 00115 pub.publish(msg); 00116 if (!ros::ok()) 00117 return 0; 00118 r.sleep(); 00119 } 00120 00121 // reset 00122 if (type != "pos") 00123 { 00124 msg.x = 0; 00125 msg.y = 0; 00126 msg.z = 0; 00127 msg.yaw = 0; 00128 } 00129 00130 for(int i=0; i<5; i++){ 00131 pub.publish(msg); 00132 r.sleep(); 00133 } 00134 00135 ros::spinOnce(); 00136 } 00137 00138 return 0; 00139 }