SlugsMAV.cc 6.27 KB
Newer Older
1 2
#include "SlugsMAV.h"

3 4
#include <QDebug>

5 6 7 8
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
        UAS(mavlink, id)//,
        // Place other initializers here
{
9
  widgetTimer = new QTimer (this);
10 11
  widgetTimer->setInterval(200);//SLUGS_UPDATE_RATE);
  qDebug() << "SLUGS_UPDATE_RATE: " << SLUGS_UPDATE_RATE;
12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37

  connect (widgetTimer, SIGNAL(timeout()),
           this, SLOT(emitSignals()));

  widgetTimer->start();

  // clear all the state structures
   memset(&mlRawImuData ,0, sizeof(mavlink_raw_imu_t));

#ifdef MAVLINK_ENABLED_SLUGS


    memset(&mlGpsData, 0, sizeof(mavlink_gps_raw_t));
    memset(&mlCpuLoadData, 0, sizeof(mavlink_cpu_load_t));
    memset(&mlAirData, 0, sizeof(mavlink_air_data_t));
    memset(&mlSensorBiasData, 0, sizeof(mavlink_sensor_bias_t));
    memset(&mlDiagnosticData, 0, sizeof(mavlink_diagnostic_t));
    memset(&mlBoot ,0, sizeof(mavlink_boot_t));
    memset(&mlGpsDateTime ,0, sizeof(mavlink_gps_date_time_t));
    memset(&mlApMode ,0, sizeof(mavlink_set_mode_t));
    memset(&mlNavigation ,0, sizeof(mavlink_slugs_navigation_t));
    memset(&mlDataLog ,0, sizeof(mavlink_data_log_t));
    memset(&mlPassthrough ,0, sizeof(mavlink_ctrl_srfc_pt_t));
    memset(&mlActionAck,0, sizeof(mavlink_action_ack_t));
    memset(&mlAction ,0, sizeof(mavlink_slugs_action_t));

38

39 40 41 42 43 44 45
    updateRoundRobin = 0;



    uasId = id;

  #endif
46 47
}

48 49 50 51 52 53 54 55
/**
 * This function is called by MAVLink once a complete, uncorrupted (CRC check valid)
 * mavlink packet is received.
 *
 * @param link Hardware link the message came from (e.g. /dev/ttyUSB0 or UDP port).
 *             messages can be sent back to the system via this link
 * @param message MAVLink message, as received from the MAVLink protocol stack
 */
56 57
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
58
    // Let UAS handle the default message set
59
   UAS::receiveMessage(link, message);
60

61
    if (message.sysid == uasId)
62
    {
63 64
#ifdef MAVLINK_ENABLED_SLUGS 
		// Handle your special messages mavlink_message_t* msg = &message;
65 66
    switch (message.msgid)
    {
67

68

69

70
      case MAVLINK_MSG_ID_RAW_IMU:
71
        //mavlink_raw_imu_t t;
72 73 74
        mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
      break;

75 76 77 78
      case MAVLINK_MSG_ID_BOOT:
        mavlink_msg_boot_decode(&message,&mlBoot);
        emit slugsBootMsg(uasId, mlBoot);
      break;
79

80 81 82
      case MAVLINK_MSG_ID_ATTITUDE:
        mavlink_msg_attitude_decode(&message, &mlAttitude);
      break;
83

84 85
      case MAVLINK_MSG_ID_GPS_RAW:
        mavlink_msg_gps_raw_decode(&message, &mlGpsData);
86
            break;
87

88 89
      case MAVLINK_MSG_ID_CPU_LOAD:       //170
        mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
90
            break;
91

92 93
      case MAVLINK_MSG_ID_AIR_DATA:       //171
        mavlink_msg_air_data_decode(&message,&mlAirData);
94 95
            break;

96 97 98
      case MAVLINK_MSG_ID_SENSOR_BIAS:    //172
        mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
      break;
99

100 101 102
      case MAVLINK_MSG_ID_DIAGNOSTIC:     //173
        mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
      break;
103

104 105
      case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
        mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
106
            break;
107

108 109 110
      case MAVLINK_MSG_ID_DATA_LOG:       //177
        mavlink_msg_data_log_decode(&message,&mlDataLog);
      break;
111

112 113
      case MAVLINK_MSG_ID_GPS_DATE_TIME:    //179
        mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
114 115
            break;

116
      case MAVLINK_MSG_ID_MID_LVL_CMDS:     //180
117
        mavlink_msg_mid_lvl_cmds_decode(&message, &mlMidLevelCommands);
118
      break;
119

120
      case MAVLINK_MSG_ID_CTRL_SRFC_PT:     //181
121
        mavlink_msg_ctrl_srfc_pt_decode(&message, &mlPassthrough);
122
            break;
123

124
      case MAVLINK_MSG_ID_SLUGS_ACTION:     //183
125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145
         mavlink_msg_slugs_action_decode(&message, &mlAction);

         switch (mlAction.actionId){
            case SLUGS_ACTION_EEPROM:
                 if (mlAction.actionVal == SLUGS_ACTION_FAIL){
                    emit textMessageReceived(message.sysid, message.compid, 255, "EEPROM Write Fail, Data was not saved in Memory!");
                 }
            break;

            case SLUGS_ACTION_PT_CHANGE:
                if (mlAction.actionVal == SLUGS_ACTION_SUCCESS){
                   emit textMessageReceived(message.sysid, message.compid, 0, "Passthrough Succesfully Changed");
                }
            break;

            case SLUGS_ACTION_MLC_CHANGE:
                if (mlAction.actionVal == SLUGS_ACTION_SUCCESS){
                   emit textMessageReceived(message.sysid, message.compid, 0, "Mid-level Commands Succesfully Changed");
                }
            break;
         }// switch actionId
146

147
      break;
148

149
      default:
150
            //        qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
151 152
            break;
        }
153
	#endif
154
    }
155
}
156 157 158



159 160 161 162 163 164 165 166 167 168 169
void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
  switch(updateRoundRobin){
    case 1:
      emit slugsCPULoad(uasId, mlCpuLoadData);
      emit slugsSensorBias(uasId,mlSensorBiasData);
    break;

    case 2:
      emit slugsAirData(uasId, mlAirData);
      emit slugsDiagnostic(uasId,mlDiagnosticData);
170

171 172 173 174 175 176 177
    break;

    case 3:
      emit slugsNavegation(uasId, mlNavigation);
      emit slugsDataLog(uasId, mlDataLog);
    break;

178
    case 4:
179
      emit slugsGPSDateTime(uasId, mlGpsDateTime);
180

181
    break;
182

183
    case 5:
184 185
      emit slugsActionAck(uasId,mlActionAck);
      emit emitGpsSignals();
186

187
    break;
188
        }
189 190 191 192 193 194 195 196

  emit slugsAttitude(uasId, mlAttitude);
  emit attitudeChanged(this,
                       mlAttitude.roll,
                       mlAttitude.pitch,
                       mlAttitude.yaw,
                       0.0);
#endif
197

198
  emit slugsRawImu(uasId, mlRawImuData);
199 200


201 202
  // wrap around
  updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
203 204


205
}
206

207 208 209
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){

210
   // qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
211 212 213 214 215


    //ToDo Uncomment if. it was comment only to test

 // if (mlGpsData.fix_type > 0){
216 217 218 219 220 221
    emit globalPositionChanged(this,
                               mlGpsData.lon,
                               mlGpsData.lat,
                               mlGpsData.alt,
                               0.0);

222 223
     emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);

224
}
225

226

Alejandro's avatar
Alejandro committed
227

228
#endif // MAVLINK_ENABLED_SLUGS