SlugsMAV.cc 8.19 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 38 39 40 41 42

  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(&mlPilotConsoleData, 0, sizeof(mavlink_pilot_console_t));
    memset(&mlFilteredData ,0, sizeof(mavlink_filtered_data_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(&mlPwmCommands ,0, sizeof(mavlink_pwm_commands_t));
    memset(&mlPidValues ,0, sizeof(mavlink_pid_values_t));
    memset(&mlSinglePid ,0, sizeof(mavlink_pid_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));

43

44 45 46 47 48 49 50
    updateRoundRobin = 0;



    uasId = id;

  #endif
51 52
}

53 54 55 56 57 58 59 60
/**
 * 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
 */
61 62
void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
63
    // Let UAS handle the default message set
64
   UAS::receiveMessage(link, message);
65

66
    if (message.sysid == uasId)
67
    {
68 69
#ifdef MAVLINK_ENABLED_SLUGS 
		// Handle your special messages mavlink_message_t* msg = &message;
70 71
    switch (message.msgid)
    {
72

73

74

75
      case MAVLINK_MSG_ID_RAW_IMU:
76
        //mavlink_raw_imu_t t;
77 78 79
        mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
      break;

80 81 82 83
      case MAVLINK_MSG_ID_BOOT:
        mavlink_msg_boot_decode(&message,&mlBoot);
        emit slugsBootMsg(uasId, mlBoot);
      break;
84

85 86 87
      case MAVLINK_MSG_ID_ATTITUDE:
        mavlink_msg_attitude_decode(&message, &mlAttitude);
      break;
88

89 90
      case MAVLINK_MSG_ID_GPS_RAW:
        mavlink_msg_gps_raw_decode(&message, &mlGpsData);
91
            break;
92

93 94
      case MAVLINK_MSG_ID_CPU_LOAD:       //170
        mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
95
            break;
96

97 98
      case MAVLINK_MSG_ID_AIR_DATA:       //171
        mavlink_msg_air_data_decode(&message,&mlAirData);
99 100
            break;

101 102 103
      case MAVLINK_MSG_ID_SENSOR_BIAS:    //172
        mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
      break;
104

105 106 107
      case MAVLINK_MSG_ID_DIAGNOSTIC:     //173
        mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
      break;
108

109 110
      case MAVLINK_MSG_ID_PILOT_CONSOLE:  //174
        mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
111
            break;
112

113 114 115
      case MAVLINK_MSG_ID_PWM_COMMANDS:   //175
        mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
      break;
116

117 118
      case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
        mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
119
            break;
120

121 122 123
      case MAVLINK_MSG_ID_DATA_LOG:       //177
        mavlink_msg_data_log_decode(&message,&mlDataLog);
      break;
124

125 126 127
      case MAVLINK_MSG_ID_FILTERED_DATA:  //178
        mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
      break;
128

129 130
      case MAVLINK_MSG_ID_GPS_DATE_TIME:    //179
        mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
131 132
            break;

133
      case MAVLINK_MSG_ID_MID_LVL_CMDS:     //180
134

135
      break;
136

137
      case MAVLINK_MSG_ID_CTRL_SRFC_PT:     //181
138

139
            break;
140

141
      case MAVLINK_MSG_ID_PID:              //182
142 143
          memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
          mavlink_msg_pid_decode(&message, &mlSinglePid);
144
        //  qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
145 146

          emit slugsPidValues(uasId, mlSinglePid);
147
      break;
148

149
      case MAVLINK_MSG_ID_SLUGS_ACTION:     //183
150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170
         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
171

172
      break;
173

174
      default:
175
            //        qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
176 177
            break;
        }
178
	#endif
179
    }
180
}
181 182 183



184 185 186 187 188 189 190 191 192 193 194
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);
195

196 197 198
    break;

    case 3:
199
      emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
200 201 202 203
       emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
        emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
         emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);

204 205 206 207 208 209 210 211 212 213 214
      emit slugsPWM(uasId, mlPwmCommands);
    break;

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

    case 5:
      emit slugsFilteredData(uasId,mlFilteredData);
      emit slugsGPSDateTime(uasId, mlGpsDateTime);
215

216
    break;
217 218 219 220

    case 6:
      emit slugsActionAck(uasId,mlActionAck);
      emit emitGpsSignals();
221

222
    break;
223
        }
224 225 226 227 228 229 230 231

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

233
  emit slugsRawImu(uasId, mlRawImuData);
234 235


236 237
  // wrap around
  updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
238 239


240
}
241

242 243 244
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){

245
   // qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
246 247 248 249 250


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

 // if (mlGpsData.fix_type > 0){
251 252 253 254 255 256
    emit globalPositionChanged(this,
                               mlGpsData.lon,
                               mlGpsData.lat,
                               mlGpsData.alt,
                               0.0);

257 258 259 260 261 262 263 264 265 266 267 268
     emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);

//        // Smaller than threshold and not NaN
//        if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
//            // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);

//         }
//         else {
//              emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
//         }
  //}

269
}
270

271 272
void SlugsMAV::emitPidSignal()
{
273
    // qDebug() << "\nSLUGS RECEIVED PID Message";
274 275 276 277
    emit slugsPidValues(uasId, mlSinglePid);

}

Alejandro's avatar
Alejandro committed
278 279 280 281 282 283

mavlink_pwm_commands_t* SlugsMAV::getPwmCommands()
{
    return &mlPwmCommands;
}

284
#endif // MAVLINK_ENABLED_SLUGS