SlugsMAV.cc 6.53 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 10 11 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
  widgetTimer = new QTimer (this);
  widgetTimer->setInterval(SLUGS_UPDATE_RATE);

  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));

42

43 44 45 46 47 48 49
    updateRoundRobin = 0;



    uasId = id;

  #endif
50 51
}

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

65

unknown's avatar
unknown committed
66
    // Handle your special messages mavlink_message_t* msg = &message;
67 68
    switch (message.msgid)
    {
69

70
#ifdef MAVLINK_ENABLED_SLUGS
71

72 73 74 75
      case MAVLINK_MSG_ID_BOOT:
        mavlink_msg_boot_decode(&message,&mlBoot);
        emit slugsBootMsg(uasId, mlBoot);
      break;
76

77 78 79
      case MAVLINK_MSG_ID_ATTITUDE:
        mavlink_msg_attitude_decode(&message, &mlAttitude);
      break;
80

81 82
      case MAVLINK_MSG_ID_GPS_RAW:
        mavlink_msg_gps_raw_decode(&message, &mlGpsData);
83
            break;
84

85 86
      case MAVLINK_MSG_ID_ACTION_ACK:      // 62
        mavlink_msg_action_ack_decode(&message,&mlActionAck);
87
            break;
88

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

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

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

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

105 106
      case MAVLINK_MSG_ID_PILOT_CONSOLE:  //174
        mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
107
            break;
108

109 110 111
      case MAVLINK_MSG_ID_PWM_COMMANDS:   //175
        mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
      break;
112

113 114
      case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
        mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
115
            break;
116

117 118 119
      case MAVLINK_MSG_ID_DATA_LOG:       //177
        mavlink_msg_data_log_decode(&message,&mlDataLog);
      break;
120

121 122 123
      case MAVLINK_MSG_ID_FILTERED_DATA:  //178
        mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
      break;
124

125 126
      case MAVLINK_MSG_ID_GPS_DATE_TIME:    //179
        mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
127 128
            break;

129
      case MAVLINK_MSG_ID_MID_LVL_CMDS:     //180
130

131
      break;
132

133
      case MAVLINK_MSG_ID_CTRL_SRFC_PT:     //181
134

135
            break;
136

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

          emit slugsPidValues(uasId, mlSinglePid);

144

145
      break;
146

147
      case MAVLINK_MSG_ID_SLUGS_ACTION:     //183
148

149
      break;
150

151
#endif
152

153 154
      default:
//        qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
155 156
            break;
        }
157
}
158 159 160



161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186
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);
    break;

    case 3:
      emit slugsPilotConsolePWM(uasId,mlPilotConsoleData);
      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);
187
    break;
188 189 190 191 192

    case 6:
      emit slugsActionAck(uasId,mlActionAck);
      emit emitGpsSignals();
    break;
193
        }
194 195 196 197 198 199 200 201

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

203
  emit slugsRawImu(uasId, mlRawImuData);
204 205


206 207
  // wrap around
  updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
208 209


210
}
211

212 213 214 215 216 217 218 219 220 221 222 223 224 225 226
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){

  if (mlGpsData.fix_type > 0){
    emit globalPositionChanged(this,
                               mlGpsData.lon,
                               mlGpsData.lat,
                               mlGpsData.alt,
                               0.0);

    // 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));
227 228 229
    }
    }
}
230

231 232 233 234 235 236 237
void SlugsMAV::emitPidSignal()
{
     qDebug() << "\nSLUGS RECEIVED PID Message";
    emit slugsPidValues(uasId, mlSinglePid);

}

238
#endif // MAVLINK_ENABLED_SLUGS