$search
00001 /* 00002 * AscTec Autopilot Telemetry 00003 * Copyright (C) 2010, CCNY Robotics Lab 00004 * Ivan Dryanovski <ivan.dryanovski@gmail.com> 00005 * William Morris <morris@ee.ccny.cuny.edu> 00006 * http://robotics.ccny.cuny.edu 00007 * 00008 * This program is free software: you can redistribute it and/or modify 00009 * it under the terms of the GNU General Public License as published by 00010 * the Free Software Foundation, either version 3 of the License, or 00011 * (at your option) any later version. 00012 * 00013 * This program is distributed in the hope that it will be useful, 00014 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00015 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00016 * GNU General Public License for more details. 00017 * 00018 * You should have received a copy of the GNU General Public License 00019 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00020 */ 00021 00022 #ifndef ASCTEC_AUTOPILOT_TELEMETRY_H 00023 #define ASCTEC_AUTOPILOT_TELEMETRY_H 00024 00025 #include "asctec_msgs/LLStatus.h" 00026 #include "asctec_msgs/IMURawData.h" 00027 #include "asctec_msgs/IMUCalcData.h" 00028 #include "asctec_msgs/RCData.h" 00029 #include "asctec_msgs/ControllerOutput.h" 00030 #include "asctec_msgs/GPSData.h" 00031 #include "asctec_msgs/GPSDataAdvanced.h" 00032 #include "asctec_msgs/CtrlInput.h" 00033 #include <std_msgs/Bool.h> 00034 00035 namespace asctec 00036 { 00037 namespace RequestTypes 00038 { 00039 enum RequestType 00040 { 00041 LL_STATUS, 00042 IMU_RAWDATA, 00043 IMU_CALCDATA, 00044 RC_DATA, 00045 CONTROLLER_OUTPUT, 00046 GPS_DATA, 00047 WAYPOINT, 00048 GPS_DATA_ADVANCED, 00049 CAM_DATA 00050 }; 00051 } 00052 typedef RequestTypes::RequestType RequestType; 00053 00068 class Telemetry 00069 { 00070 public: 00077 Telemetry(ros::NodeHandle nh); 00083 ~Telemetry(); 00084 00098 void buildRequest (); 00099 00113 void enablePolling (RequestType msg, uint8_t interval = 1, uint8_t offset = 0); 00114 std::string requestToString(RequestTypes::RequestType t); 00115 void publishPackets(); 00116 00117 void enableControl (Telemetry * telemetry_, uint8_t interval = 1, uint8_t offset = 0); 00118 00119 void dumpLL_STATUS(); 00120 void dumpIMU_RAWDATA(); 00121 void dumpIMU_CALCDATA(); 00122 void dumpRC_DATA(); 00123 void dumpCONTROLLER_OUTPUT(); 00124 void dumpGPS_DATA(); 00125 void dumpGPS_DATA_ADVANCED(); 00126 void dumpCTRL_INPUT(); 00127 00128 void copyLL_STATUS(); 00129 void copyIMU_RAWDATA(); 00130 void copyIMU_CALCDATA(); 00131 void copyRC_DATA(); 00132 void copyCONTROLLER_OUTPUT(); 00133 void copyGPS_DATA(); 00134 void copyGPS_DATA_ADVANCED(); 00135 void copyCTRL_INPUT(asctec_msgs::CtrlInput msg); 00136 void estopCallback(const std_msgs::Bool msg); 00137 00138 bool pollingEnabled_; 00139 bool controlEnabled_; 00140 uint16_t requestCount_; 00141 uint16_t controlCount_; 00142 std::bitset < 16 > requestPackets_; 00143 00144 static const uint8_t REQUEST_TYPES = 9; 00145 /* 00146 static const uint16_t REQUEST_BITMASK[REQUEST_TYPES] = { 00147 0x0001, 0x0002, 0x0004, 0x0008, 0x0010, 0x0080, 0x0100, 0x0200, 0x0800 }; 00148 */ 00149 uint16_t REQUEST_BITMASK[REQUEST_TYPES]; 00150 uint8_t requestInterval_[REQUEST_TYPES]; 00151 uint8_t requestOffset_[REQUEST_TYPES]; 00152 ros::Publisher requestPublisher_[REQUEST_TYPES]; 00153 ros::Time timestamps_[REQUEST_TYPES]; 00154 00155 uint8_t controlInterval_; 00156 uint8_t controlOffset_; 00157 ros::Subscriber controlSubscriber_; 00158 ros::Subscriber estopSubscriber_; 00159 00160 //packet descriptors 00161 static const uint8_t PD_IMURAWDATA = 0x01; 00162 static const uint8_t PD_LLSTATUS = 0x02; 00163 static const uint8_t PD_IMUCALCDATA = 0x03; 00164 static const uint8_t PD_HLSTATUS = 0x04; 00165 static const uint8_t PD_DEBUGDATA = 0x05; 00166 00167 static const uint8_t PD_CTRLOUT = 0x11; 00168 static const uint8_t PD_FLIGHTPARAMS = 0x12; 00169 static const uint8_t PD_CTRLCOMMANDS = 0x13; 00170 static const uint8_t PD_CTRLINTERNAL = 0x14; 00171 static const uint8_t PD_RCDATA = 0x15; 00172 static const uint8_t PD_CTRLSTATUS = 0x16; 00173 static const uint8_t PD_CTRLINPUT = 0x17; 00174 static const uint8_t PD_CTRLFALCON = 0x18; 00175 00176 static const uint8_t PD_WAYPOINT = 0x20; 00177 static const uint8_t PD_CURRENTWAY = 0x21; 00178 static const uint8_t PD_NMEADATA = 0x22; 00179 static const uint8_t PD_GPSDATA = 0x23; 00180 static const uint8_t PD_SINGLEWAYPOINT = 0x24; 00181 static const uint8_t PD_GOTOCOMMAND = 0x25; 00182 static const uint8_t PD_LAUNCHCOMMAND = 0x26; 00183 static const uint8_t PD_LANDCOMMAND = 0x27; 00184 static const uint8_t PD_HOMECOMMAND = 0x28; 00185 static const uint8_t PD_GPSDATAADVANCED = 0x29; 00186 00187 static const uint8_t PD_CAMERACOMMANDS = 0x30; 00188 00189 struct LL_STATUS 00190 { 00191 //battery voltages in mV 00192 short battery_voltage_1; 00193 short battery_voltage_2; 00194 //don’t care 00195 short status; 00196 //Controller cycles per second (should be ˜1000) 00197 short cpu_load; 00198 //don’t care 00199 char compass_enabled; 00200 char chksum_error; 00201 char flying; 00202 char motors_on; 00203 short flightMode; 00204 //Time motors are turning 00205 short up_time; 00206 }; 00207 00208 struct IMU_RAWDATA 00209 { 00210 //pressure sensor 24-bit value, not scaled but bias free 00211 int pressure; 00212 //16-bit gyro readings; 32768 = 2.5V 00213 short gyro_x; 00214 short gyro_y; 00215 short gyro_z; 00216 //10-bit magnetic field sensor readings 00217 short mag_x; 00218 short mag_y; 00219 short mag_z; 00220 //16-bit accelerometer readings 00221 short acc_x; 00222 short acc_y; 00223 short acc_z; 00224 //16-bit temperature measurement using yaw-gyro internal sensor 00225 unsigned short temp_gyro; 00226 //16-bit temperature measurement using ADC internal sensor 00227 unsigned int temp_ADC; 00228 }; 00229 00230 struct IMU_CALCDATA 00231 { 00232 // angles derived by integration of gyro_outputs, drift compensated by data fusion; 00233 // -90000..+90000 pitch(nick) and roll, 0..360000 yaw; 1000 = 1 degree 00234 int angle_nick; 00235 int angle_roll; 00236 int angle_yaw; 00237 // angular velocities, raw values [16 bit] but bias free 00238 int angvel_nick; 00239 int angvel_roll; 00240 int angvel_yaw; 00241 // acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g 00242 short acc_x_calib; 00243 short acc_y_calib; 00244 short acc_z_calib; 00245 // horizontal / vertical accelerations: -10000..+10000 = -1g..+1g 00246 short acc_x; 00247 short acc_y; 00248 short acc_z; 00249 // reference angles derived by accelerations only: -90000..+90000; 1000 = 1 degree 00250 int acc_angle_nick; 00251 int acc_angle_roll; 00252 // total acceleration measured (10000 = 1g) 00253 int acc_absolute_value; 00254 // magnetic field sensors output, offset free and scaled; 00255 // units not determined, as only the direction of the field vector is taken into account 00256 int Hx; 00257 int Hy; 00258 int Hz; 00259 00260 //compass reading: angle reference for angle_yaw: 0..360000; 1000 = 1 degree 00261 int mag_heading; 00262 //pseudo speed measurements: integrated accelerations, pulled towards zero; units unknown; used for short-term position stabilization 00263 int speed_x; 00264 int speed_y; 00265 int speed_z; 00266 //height in mm (after data fusion) 00267 int height; 00268 //diff. height in mm/s (after data fusion) 00269 int dheight; 00270 //diff. height measured by the pressure sensor [mm/s] 00271 int dheight_reference; 00272 //height measured by the pressure sensor [mm] 00273 int height_reference; 00274 }; 00275 00276 struct RC_DATA 00277 { 00278 //channels as read from R/C receiver 00279 unsigned short channels_in[8]; 00280 //channels bias free, remapped and scaled to 0..4095 00281 unsigned short channels_out[8]; 00282 //Indicator for valid R/C receiption 00283 unsigned char lock; 00284 }; 00285 00286 struct CONTROLLER_OUTPUT 00287 { 00288 //attitude controller outputs; 0..200 = -100 ..+100% 00289 int nick; 00290 int roll; 00291 int yaw; 00292 //current thrust (height controller output); 0..200 = 0..100% 00293 int thrust; 00294 }; 00295 00296 struct GPS_DATA 00297 { 00298 //latitude/longitude in deg * 10ˆ7 00299 int latitude; 00300 int longitude; 00301 //GPS height in mm 00302 int height; 00303 //speed in x (E/W) and y(N/S) in mm/s 00304 int speed_x; 00305 int speed_y; 00306 //GPS heading in deg * 1000 00307 int heading; 00308 //accuracy estimates in mm and mm/s 00309 unsigned int horizontal_accuracy; 00310 unsigned int vertical_accuracy; 00311 unsigned int speed_accuracy; 00312 //number of satellite vehicles used in NAV solution 00313 unsigned int numSV; 00314 // GPS status information; 0x03 = valid GPS fix 00315 int status; 00316 }; 00317 00318 struct GPS_DATA_ADVANCED 00319 { 00320 //latitude/longitude in deg * 10ˆ7 00321 int latitude; 00322 int longitude; 00323 //GPS height in mm 00324 int height; 00325 //speed in x (E/W) and y(N/S) in mm/s 00326 int speed_x; 00327 int speed_y; 00328 //GPS heading in deg * 1000 00329 int heading; 00330 //accuracy estimates in mm and mm/s 00331 unsigned int horizontal_accuracy; 00332 unsigned int vertical_accuracy; 00333 unsigned int speed_accuracy; 00334 //number of satellite vehicles used in NAV solution 00335 unsigned int numSV; 00336 00337 //GPS status information; 0x03 = valid GPS fix 00338 int status; 00339 //coordinates of current origin in deg * 10ˆ7RCData_ 00340 int latitude_best_estimate; 00341 int longitude_best_estimate; 00342 //velocities in X (E/W) and Y (N/S) after data fusion 00343 int speed_x_best_estimate; 00344 int speed_y_best_estimate; 00345 }; 00346 00347 struct WAYPOINT 00348 { 00349 //always set to 1 00350 unsigned char wp_number; 00351 //don't care 00352 unsigned char dummy_1; 00353 unsigned short dummy_2; 00354 //see WPPROP defines below 00355 unsigned char properties; 00356 //max. speed to travel to waypoint in % (default 100) 00357 unsigned char max_speed; 00358 //time to stay at a waypoint (XYZ) in 1/100th s 00359 unsigned short time; 00360 //position accuracy to consider a waypoint reached in mm (default: 2500 (= 2.5 m)) 00361 unsigned short pos_acc; 00362 //chksum = 0xAAAA + wp.yaw + wp.height + wp.time + wp.X + wp.Y + wp.max_speed + wp.pos_acc + wp.properties + wp.wp_number; 00363 short chksum; 00364 //waypoint coordinates in mm // longitude in abs coords 00365 int X; 00366 //waypoint coordinates in mm // latitude in abs coords 00367 int Y; 00368 //Desired heading at waypoint 00369 int yaw; 00370 //height over 0 reference in mm 00371 int height; 00372 }; 00373 struct CTRL_INPUT 00374 { 00375 //serial commands (= Scientific Interface) 00376 //pitch input: -2047..2047 (0=neutral) 00377 short pitch; 00378 //roll input: -2047..2047 (0=neutral) 00379 short roll; 00380 //R/C stick input: -2047..2047 (0=neutral) 00381 short yaw; 00382 //collective: 0..4095 = 0..100% 00383 short thrust; 00384 //control byte: 00385 // bit 0: pitch control enabled 00386 // bit 1: roll control enabled 00387 // bit 2: yaw control enabled 00388 // bit 3: thrust control enabled 00389 // These bits can be used to only enable one axis at a time and thus to 00390 // control the other axes manually. This usually helps a lot to set up 00391 // and finetune controllers for each axis seperately. 00392 short ctrl; 00393 short chksum; 00394 }; 00395 00396 /* 00397 00398 #define WPPROP_ABSCOORDS 0x01 //if set waypoint is interpreted as 00399 absolute coordinates, else relative coords 00400 #define WPPROP_HEIGHTENABLED 0x02 //set new height at waypoint 00401 #define WPPROP_YAWENABLED 0x04 //set new yaw-angle at waypoint 00402 (not yet implemented) 00403 #define WPPROP_AUTOMATICGOTO 0x10 //if set, vehicle will not wait for 00404 a goto command, but goto this waypoint directly 00405 #define WPPROP_CAM_TRIGGER 0x20 //if set, photo camera is triggered 00406 when waypoint is reached and time to stay is 80% up 00407 Sending the waypoint structure to the vehicle: 00408 The following string must be sent to the vehicle, directly followed by the actual waypoint 00409 structure: 00410 unsigned char string[]=">*>ws"; 00411 Commands for the waypoint navigation: 00412 >*>wg "Goto waypoint" 00413 >*>wl "Launch / Set Home 00414 >*>we "End flight => land at current position" 00415 >*>wh "Come home" 00416 Sending the launch command when the vehicle is hovering with the switch on the R/C in 00417 "GPS + Height control" sets the home position. 00418 You will receive an acknowledge if a command or a waypoint was received correctly: 00419 >a[1 byte packet descriptor]a< 00420 00421 */ 00422 00423 struct LL_STATUS LL_STATUS_; 00424 struct IMU_RAWDATA IMU_RAWDATA_; 00425 struct IMU_CALCDATA IMU_CALCDATA_; 00426 struct RC_DATA RC_DATA_; 00427 struct CONTROLLER_OUTPUT CONTROLLER_OUTPUT_; 00428 struct GPS_DATA GPS_DATA_; 00429 struct WAYPOINT WAYPOINT_; 00430 struct GPS_DATA_ADVANCED GPS_DATA_ADVANCED_; 00431 struct CTRL_INPUT CTRL_INPUT_; 00432 asctec_msgs::LLStatusPtr LLStatus_; 00433 asctec_msgs::IMURawDataPtr IMURawData_; 00434 asctec_msgs::IMUCalcDataPtr IMUCalcData_; 00435 asctec_msgs::RCDataPtr RCData_; 00436 asctec_msgs::ControllerOutputPtr ControllerOutput_; 00437 asctec_msgs::GPSDataPtr GPSData_; 00438 asctec_msgs::GPSDataAdvancedPtr GPSDataAdvanced_; 00439 00440 ros::NodeHandle nh_; 00441 //asctec_msgs::CtrlInput CtrlInput_; 00442 bool estop_; 00443 00444 }; // end class Telemetry 00445 } //end namespace asctec 00446 #endif