00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
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
00147
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
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
00192 short battery_voltage_1;
00193 short battery_voltage_2;
00194
00195 short status;
00196
00197 short cpu_load;
00198
00199 char compass_enabled;
00200 char chksum_error;
00201 char flying;
00202 char motors_on;
00203 short flightMode;
00204
00205 short up_time;
00206 };
00207
00208 struct IMU_RAWDATA
00209 {
00210
00211 int pressure;
00212
00213 short gyro_x;
00214 short gyro_y;
00215 short gyro_z;
00216
00217 short mag_x;
00218 short mag_y;
00219 short mag_z;
00220
00221 short acc_x;
00222 short acc_y;
00223 short acc_z;
00224
00225 unsigned short temp_gyro;
00226
00227 unsigned int temp_ADC;
00228 };
00229
00230 struct IMU_CALCDATA
00231 {
00232
00233
00234 int angle_nick;
00235 int angle_roll;
00236 int angle_yaw;
00237
00238 int angvel_nick;
00239 int angvel_roll;
00240 int angvel_yaw;
00241
00242 short acc_x_calib;
00243 short acc_y_calib;
00244 short acc_z_calib;
00245
00246 short acc_x;
00247 short acc_y;
00248 short acc_z;
00249
00250 int acc_angle_nick;
00251 int acc_angle_roll;
00252
00253 int acc_absolute_value;
00254
00255
00256 int Hx;
00257 int Hy;
00258 int Hz;
00259
00260
00261 int mag_heading;
00262
00263 int speed_x;
00264 int speed_y;
00265 int speed_z;
00266
00267 int height;
00268
00269 int dheight;
00270
00271 int dheight_reference;
00272
00273 int height_reference;
00274 };
00275
00276 struct RC_DATA
00277 {
00278
00279 unsigned short channels_in[8];
00280
00281 unsigned short channels_out[8];
00282
00283 unsigned char lock;
00284 };
00285
00286 struct CONTROLLER_OUTPUT
00287 {
00288
00289 int nick;
00290 int roll;
00291 int yaw;
00292
00293 int thrust;
00294 };
00295
00296 struct GPS_DATA
00297 {
00298
00299 int latitude;
00300 int longitude;
00301
00302 int height;
00303
00304 int speed_x;
00305 int speed_y;
00306
00307 int heading;
00308
00309 unsigned int horizontal_accuracy;
00310 unsigned int vertical_accuracy;
00311 unsigned int speed_accuracy;
00312
00313 unsigned int numSV;
00314
00315 int status;
00316 };
00317
00318 struct GPS_DATA_ADVANCED
00319 {
00320
00321 int latitude;
00322 int longitude;
00323
00324 int height;
00325
00326 int speed_x;
00327 int speed_y;
00328
00329 int heading;
00330
00331 unsigned int horizontal_accuracy;
00332 unsigned int vertical_accuracy;
00333 unsigned int speed_accuracy;
00334
00335 unsigned int numSV;
00336
00337
00338 int status;
00339
00340 int latitude_best_estimate;
00341 int longitude_best_estimate;
00342
00343 int speed_x_best_estimate;
00344 int speed_y_best_estimate;
00345 };
00346
00347 struct WAYPOINT
00348 {
00349
00350 unsigned char wp_number;
00351
00352 unsigned char dummy_1;
00353 unsigned short dummy_2;
00354
00355 unsigned char properties;
00356
00357 unsigned char max_speed;
00358
00359 unsigned short time;
00360
00361 unsigned short pos_acc;
00362
00363 short chksum;
00364
00365 int X;
00366
00367 int Y;
00368
00369 int yaw;
00370
00371 int height;
00372 };
00373 struct CTRL_INPUT
00374 {
00375
00376
00377 short pitch;
00378
00379 short roll;
00380
00381 short yaw;
00382
00383 short thrust;
00384
00385
00386
00387
00388
00389
00390
00391
00392 short ctrl;
00393 short chksum;
00394 };
00395
00396
00397
00398
00399
00400
00401
00402
00403
00404
00405
00406
00407
00408
00409
00410
00411
00412
00413
00414
00415
00416
00417
00418
00419
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
00442 bool estop_;
00443
00444 };
00445 }
00446 #endif