SlugsMAV.cc 9.03 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
      case MAVLINK_MSG_ID_HEARTBEAT:
71 72 73
        emit heartbeat(this);
        // Set new type if it has changed
        if (this->type != mavlink_msg_heartbeat_get_type(&message))
74
        {
75 76
            this->type = mavlink_msg_heartbeat_get_type(&message);
            emit systemTypeSet(this, type);
77
        }
78
      break;
tecnosapiens's avatar
tecnosapiens committed
79

80 81
      case MAVLINK_MSG_ID_RAW_IMU:
        mavlink_msg_raw_imu_decode(&message, &mlRawImuData);
82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132
      break;

      case MAVLINK_MSG_ID_WAYPOINT_COUNT:
        mavlink_waypoint_count_t wpct;
        mavlink_msg_waypoint_count_decode(&message, &wpct);
        if (wpct.target_system == mavlink->getSystemId() && wpct.target_component == mavlink->getComponentId())
        {
          waypointManager.handleWaypointCount(message.sysid, message.compid, wpct.count);
        }
      break;

      case MAVLINK_MSG_ID_WAYPOINT:
        mavlink_waypoint_t wp;
        mavlink_msg_waypoint_decode(&message, &wp);
        //qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
        if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
        {
          waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
        }
      break;

      case MAVLINK_MSG_ID_WAYPOINT_ACK:
        mavlink_waypoint_ack_t wpa;
        mavlink_msg_waypoint_ack_decode(&message, &wpa);
        if(wpa.target_system == mavlink->getSystemId() && wpa.target_component == mavlink->getComponentId())
        {
          waypointManager.handleWaypointAck(message.sysid, message.compid, &wpa);
        }
      break;

      case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
        mavlink_waypoint_request_t wpr;
        mavlink_msg_waypoint_request_decode(&message, &wpr);
        qDebug() << "Waypoint Request" << wpr.seq;
        if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
        {
          waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
        }
      break;

      case MAVLINK_MSG_ID_WAYPOINT_REACHED:
        mavlink_waypoint_reached_t wpre;
        mavlink_msg_waypoint_reached_decode(&message, &wpre);
        waypointManager.handleWaypointReached(message.sysid, message.compid, &wpre);
      break;

      case MAVLINK_MSG_ID_WAYPOINT_CURRENT:
        mavlink_waypoint_current_t wpc;
        mavlink_msg_waypoint_current_decode(&message, &wpc);
        waypointManager.handleWaypointCurrent(message.sysid, message.compid, &wpc);
      break;
133

134
#ifdef MAVLINK_ENABLED_SLUGS
135

136 137 138 139
      case MAVLINK_MSG_ID_BOOT:
        mavlink_msg_boot_decode(&message,&mlBoot);
        emit slugsBootMsg(uasId, mlBoot);
      break;
140

141 142 143
      case MAVLINK_MSG_ID_ATTITUDE:
        mavlink_msg_attitude_decode(&message, &mlAttitude);
      break;
144

145 146
      case MAVLINK_MSG_ID_GPS_RAW:
        mavlink_msg_gps_raw_decode(&message, &mlGpsData);
147
            break;
148

149 150
      case MAVLINK_MSG_ID_ACTION_ACK:      // 62
        mavlink_msg_action_ack_decode(&message,&mlActionAck);
151
            break;
152

153 154
      case MAVLINK_MSG_ID_CPU_LOAD:       //170
        mavlink_msg_cpu_load_decode(&message,&mlCpuLoadData);
155
            break;
156

157 158
      case MAVLINK_MSG_ID_AIR_DATA:       //171
        mavlink_msg_air_data_decode(&message,&mlAirData);
159 160
            break;

161 162 163
      case MAVLINK_MSG_ID_SENSOR_BIAS:    //172
        mavlink_msg_sensor_bias_decode(&message,&mlSensorBiasData);
      break;
164

165 166 167
      case MAVLINK_MSG_ID_DIAGNOSTIC:     //173
        mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
      break;
168

169 170
      case MAVLINK_MSG_ID_PILOT_CONSOLE:  //174
        mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
171
            break;
172

173 174 175
      case MAVLINK_MSG_ID_PWM_COMMANDS:   //175
        mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
      break;
176

177 178
      case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
        mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
179
            break;
180

181 182 183
      case MAVLINK_MSG_ID_DATA_LOG:       //177
        mavlink_msg_data_log_decode(&message,&mlDataLog);
      break;
184

185 186 187
      case MAVLINK_MSG_ID_FILTERED_DATA:  //178
        mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
      break;
188

189 190
      case MAVLINK_MSG_ID_GPS_DATE_TIME:    //179
        mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
191 192
            break;

193
      case MAVLINK_MSG_ID_MID_LVL_CMDS:     //180
194

195
      break;
196

197
      case MAVLINK_MSG_ID_CTRL_SRFC_PT:     //181
198

199
            break;
200

201
      case MAVLINK_MSG_ID_PID:              //182
202 203 204 205 206 207
          memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
          mavlink_msg_pid_decode(&message, &mlSinglePid);
          qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;

          emit slugsPidValues(uasId, mlSinglePid);

208

209
      break;
210

211
      case MAVLINK_MSG_ID_SLUGS_ACTION:     //183
212

213
      break;
214

215
#endif
216

217 218
      default:
//        qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
219 220
            break;
        }
221
}
222 223 224



225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250
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);
251
    break;
252 253 254 255 256

    case 6:
      emit slugsActionAck(uasId,mlActionAck);
      emit emitGpsSignals();
    break;
257
        }
258 259 260 261 262 263 264 265

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

267
  emit slugsRawImu(uasId, mlRawImuData);
268 269


270 271
  // wrap around
  updateRoundRobin = updateRoundRobin > 10? 1: updateRoundRobin + 1;
272 273


274
}
275

276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
#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));
291 292 293
    }
    }
}
294

295 296 297 298 299 300 301
void SlugsMAV::emitPidSignal()
{
     qDebug() << "\nSLUGS RECEIVED PID Message";
    emit slugsPidValues(uasId, mlSinglePid);

}

302
#endif // MAVLINK_ENABLED_SLUGS