PX4FirmwarePlugin.cc 13.9 KB
Newer Older
Don Gagne's avatar
Don Gagne committed
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

Don Gagne's avatar
Don Gagne committed
3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

Don Gagne's avatar
Don Gagne committed
5
 (c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

Don Gagne's avatar
Don Gagne committed
7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

Don Gagne's avatar
Don Gagne committed
9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
dogmaphobic's avatar
dogmaphobic committed
13

Don Gagne's avatar
Don Gagne committed
14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
dogmaphobic's avatar
dogmaphobic committed
18

Don Gagne's avatar
Don Gagne committed
19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

Don Gagne's avatar
Don Gagne committed
22 23 24 25 26 27
 ======================================================================*/

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "PX4FirmwarePlugin.h"
28
#include "PX4ParameterMetaData.h"
29
#include "QGCApplication.h"
30
#include "AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h"    // FIXME: Hack
Don Gagne's avatar
Don Gagne committed
31 32 33 34 35 36 37 38 39 40 41

#include <QDebug>

enum PX4_CUSTOM_MAIN_MODE {
    PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
    PX4_CUSTOM_MAIN_MODE_ALTCTL,
    PX4_CUSTOM_MAIN_MODE_POSCTL,
    PX4_CUSTOM_MAIN_MODE_AUTO,
    PX4_CUSTOM_MAIN_MODE_ACRO,
    PX4_CUSTOM_MAIN_MODE_OFFBOARD,
    PX4_CUSTOM_MAIN_MODE_STABILIZED,
42
    PX4_CUSTOM_MAIN_MODE_RATTITUDE
Don Gagne's avatar
Don Gagne committed
43 44 45 46 47 48 49 50 51
};

enum PX4_CUSTOM_SUB_MODE_AUTO {
    PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
    PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
    PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
    PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
    PX4_CUSTOM_SUB_MODE_AUTO_RTL,
    PX4_CUSTOM_SUB_MODE_AUTO_LAND,
Jimmy Johnson's avatar
Jimmy Johnson committed
52 53
    PX4_CUSTOM_SUB_MODE_AUTO_RTGS,
    PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_ME
Don Gagne's avatar
Don Gagne committed
54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72
};

union px4_custom_mode {
    struct {
        uint16_t reserved;
        uint8_t main_mode;
        uint8_t sub_mode;
    };
    uint32_t data;
    float data_float;
};

struct Modes2Name {
    uint8_t     main_mode;
    uint8_t     sub_mode;
    const char* name;       ///< Name for flight mode
    bool        canBeSet;   ///< true: Vehicle can be set to this flight mode
};

Don Gagne's avatar
Don Gagne committed
73 74 75 76 77 78 79 80 81
const char* PX4FirmwarePlugin::manualFlightMode =       "Manual";
const char* PX4FirmwarePlugin::acroFlightMode =         "Acro";
const char* PX4FirmwarePlugin::stabilizedFlightMode =   "Stabilized";
const char* PX4FirmwarePlugin::rattitudeFlightMode =    "Rattitude";
const char* PX4FirmwarePlugin::altCtlFlightMode =       "Altitude Control";
const char* PX4FirmwarePlugin::posCtlFlightMode =       "Position Control";
const char* PX4FirmwarePlugin::offboardFlightMode =     "Offboard Control";
const char* PX4FirmwarePlugin::readyFlightMode =        "Ready";
const char* PX4FirmwarePlugin::takeoffFlightMode =      "Takeoff";
82
const char* PX4FirmwarePlugin::pauseFlightMode =        "Hold";
Don Gagne's avatar
Don Gagne committed
83 84 85 86
const char* PX4FirmwarePlugin::missionFlightMode =      "Mission";
const char* PX4FirmwarePlugin::rtlFlightMode =          "Return To Land";
const char* PX4FirmwarePlugin::landingFlightMode =      "Landing";
const char* PX4FirmwarePlugin::rtgsFlightMode =         "Return, Link Loss";
Jimmy Johnson's avatar
Jimmy Johnson committed
87
const char* PX4FirmwarePlugin::followMeFlightMode =     "Follow Me";
Don Gagne's avatar
Don Gagne committed
88

Don Gagne's avatar
Don Gagne committed
89
/// Tranlates from PX4 custom modes to flight mode names
90

Don Gagne's avatar
Don Gagne committed
91
static const struct Modes2Name rgModes2Name[] = {
Don Gagne's avatar
Don Gagne committed
92 93 94 95 96 97 98 99 100 101 102 103 104 105
    { PX4_CUSTOM_MAIN_MODE_MANUAL,      0,                                  PX4FirmwarePlugin::manualFlightMode,        true },
    { PX4_CUSTOM_MAIN_MODE_ACRO,        0,                                  PX4FirmwarePlugin::acroFlightMode,          true },
    { PX4_CUSTOM_MAIN_MODE_STABILIZED,  0,                                  PX4FirmwarePlugin::stabilizedFlightMode,    true },
    { PX4_CUSTOM_MAIN_MODE_RATTITUDE,   0,                                  PX4FirmwarePlugin::rattitudeFlightMode,     true },
    { PX4_CUSTOM_MAIN_MODE_ALTCTL,      0,                                  PX4FirmwarePlugin::altCtlFlightMode,        true },
    { PX4_CUSTOM_MAIN_MODE_POSCTL,      0,                                  PX4FirmwarePlugin::posCtlFlightMode,        true },
    { PX4_CUSTOM_MAIN_MODE_OFFBOARD,    0,                                  PX4FirmwarePlugin::offboardFlightMode,      true },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_READY,     PX4FirmwarePlugin::readyFlightMode,         false },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,   PX4FirmwarePlugin::takeoffFlightMode,       false },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LOITER,    PX4FirmwarePlugin::pauseFlightMode,         true },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_MISSION,   PX4FirmwarePlugin::missionFlightMode,       true },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTL,       PX4FirmwarePlugin::rtlFlightMode,           true },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LAND,      PX4FirmwarePlugin::landingFlightMode,       false },
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTGS,      PX4FirmwarePlugin::rtgsFlightMode,          false },
Jimmy Johnson's avatar
Jimmy Johnson committed
106
    { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_ME, PX4FirmwarePlugin::followMeFlightMode,      true },
Don Gagne's avatar
Don Gagne committed
107 108 109 110 111
};

QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
    Q_UNUSED(vehicle);
dogmaphobic's avatar
dogmaphobic committed
112

Don Gagne's avatar
Don Gagne committed
113 114 115 116 117 118
    return QList<VehicleComponent*>();
}

QStringList PX4FirmwarePlugin::flightModes(void)
{
    QStringList flightModes;
dogmaphobic's avatar
dogmaphobic committed
119

Don Gagne's avatar
Don Gagne committed
120 121
    for (size_t i=0; i<sizeof(rgModes2Name)/sizeof(rgModes2Name[0]); i++) {
        const struct Modes2Name* pModes2Name = &rgModes2Name[i];
dogmaphobic's avatar
dogmaphobic committed
122

Don Gagne's avatar
Don Gagne committed
123 124 125 126
        if (pModes2Name->canBeSet) {
            flightModes += pModes2Name->name;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
127

Don Gagne's avatar
Don Gagne committed
128 129 130
    return flightModes;
}

Don Gagne's avatar
Don Gagne committed
131
QString PX4FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
Don Gagne's avatar
Don Gagne committed
132 133
{
    QString flightMode = "Unknown";
dogmaphobic's avatar
dogmaphobic committed
134

Don Gagne's avatar
Don Gagne committed
135 136 137
    if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
        union px4_custom_mode px4_mode;
        px4_mode.data = custom_mode;
dogmaphobic's avatar
dogmaphobic committed
138

Don Gagne's avatar
Don Gagne committed
139 140 141
        bool found = false;
        for (size_t i=0; i<sizeof(rgModes2Name)/sizeof(rgModes2Name[0]); i++) {
            const struct Modes2Name* pModes2Name = &rgModes2Name[i];
dogmaphobic's avatar
dogmaphobic committed
142

Don Gagne's avatar
Don Gagne committed
143 144 145 146 147 148
            if (pModes2Name->main_mode == px4_mode.main_mode && pModes2Name->sub_mode == px4_mode.sub_mode) {
                flightMode = pModes2Name->name;
                found = true;
                break;
            }
        }
dogmaphobic's avatar
dogmaphobic committed
149

Don Gagne's avatar
Don Gagne committed
150 151 152 153 154 155
        if (!found) {
            qWarning() << "Unknown flight mode" << custom_mode;
        }
    } else {
        qWarning() << "PX4 Flight Stack flight mode without custom mode enabled?";
    }
dogmaphobic's avatar
dogmaphobic committed
156

Don Gagne's avatar
Don Gagne committed
157 158 159 160 161 162 163
    return flightMode;
}

bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
    *base_mode = 0;
    *custom_mode = 0;
dogmaphobic's avatar
dogmaphobic committed
164

Don Gagne's avatar
Don Gagne committed
165 166 167
    bool found = false;
    for (size_t i=0; i<sizeof(rgModes2Name)/sizeof(rgModes2Name[0]); i++) {
        const struct Modes2Name* pModes2Name = &rgModes2Name[i];
dogmaphobic's avatar
dogmaphobic committed
168

Don Gagne's avatar
Don Gagne committed
169 170 171 172 173 174
        if (flightMode.compare(pModes2Name->name, Qt::CaseInsensitive) == 0) {
            union px4_custom_mode px4_mode;

            px4_mode.data = 0;
            px4_mode.main_mode = pModes2Name->main_mode;
            px4_mode.sub_mode = pModes2Name->sub_mode;
dogmaphobic's avatar
dogmaphobic committed
175

Don Gagne's avatar
Don Gagne committed
176 177
            *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
            *custom_mode = px4_mode.data;
dogmaphobic's avatar
dogmaphobic committed
178

Don Gagne's avatar
Don Gagne committed
179 180 181 182
            found = true;
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
183

Don Gagne's avatar
Don Gagne committed
184 185 186
    if (!found) {
        qWarning() << "Unknown flight Mode" << flightMode;
    }
dogmaphobic's avatar
dogmaphobic committed
187

Don Gagne's avatar
Don Gagne committed
188 189
    return found;
}
190 191 192

int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
{
193
    return 0;   // 0 buttons reserved for rc switch simulation
194
}
Don Gagne's avatar
Don Gagne committed
195

Don Gagne's avatar
Don Gagne committed
196 197
bool PX4FirmwarePlugin::isCapable(FirmwareCapabilities capabilities)
{
198
    return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability)) == capabilities;
Don Gagne's avatar
Don Gagne committed
199
}
200 201 202 203

void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
    Q_UNUSED(vehicle);
dogmaphobic's avatar
dogmaphobic committed
204

205 206
    // PX4 Flight Stack doesn't need to do any extra work
}
207 208 209 210 211 212 213

bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
{
    // PX4 stack does not want home position sent in the first position.
    // Subsequent sequence numbers must be adjusted.
    return false;
}
214

215
void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
216
{
217 218 219 220 221 222 223
    PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);

    if (px4MetaData) {
        px4MetaData->addMetaDataToFact(fact, vehicleType);
    } else {
        qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData";
    }
224
}
Don Gagne's avatar
Don Gagne committed
225 226 227 228 229

QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{
    QList<MAV_CMD> list;

230
    list << MAV_CMD_NAV_WAYPOINT
231
         << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME
Don Gagne's avatar
Don Gagne committed
232
         << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
233
         << MAV_CMD_DO_JUMP
Don Gagne's avatar
Don Gagne committed
234
         << MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
235
         << MAV_CMD_DO_DIGICAM_CONTROL
236
         << MAV_CMD_DO_SET_CAM_TRIGG_DIST
237
         << MAV_CMD_DO_SET_SERVO
Don Gagne's avatar
Don Gagne committed
238
         << MAV_CMD_DO_CHANGE_SPEED
Don Gagne's avatar
Don Gagne committed
239
         << MAV_CMD_NAV_PATHPLANNING;
Jimmy Johnson's avatar
Jimmy Johnson committed
240

Don Gagne's avatar
Don Gagne committed
241 242
    return list;
}
243 244 245 246 247 248 249 250

void PX4FirmwarePlugin::missionCommandOverrides(QString& commonJsonFilename, QString& fixedWingJsonFilename, QString& multiRotorJsonFilename) const
{
    // No overrides
    commonJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoCommon.json");
    fixedWingJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
    multiRotorJsonFilename = QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
}
251 252 253 254 255 256 257

QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
    PX4ParameterMetaData* metaData = new PX4ParameterMetaData;
    metaData->loadParameterFactMetaDataFile(metaDataFile);
    return metaData;
}
Don Gagne's avatar
Don Gagne committed
258 259 260

void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
261 262
    // then tell it to loiter at the current position
    mavlink_message_t msg;
Lorenz Meier's avatar
Lorenz Meier committed
263
    mavlink_command_long_t cmd;
264 265 266 267

    cmd.command = (uint16_t)MAV_CMD_DO_REPOSITION;
    cmd.confirmation = 0;
    cmd.param1 = -1.0f;
268
    cmd.param2 = MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
269 270 271 272 273 274 275 276 277 278 279 280
    cmd.param3 = 0.0f;
    cmd.param4 = NAN;
    cmd.param5 = NAN;
    cmd.param6 = NAN;
    cmd.param7 = NAN;
    cmd.target_system = vehicle->id();
    cmd.target_component = 0;

    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);

    vehicle->sendMessage(msg);
Don Gagne's avatar
Don Gagne committed
281
}
282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300

void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle)
{
    vehicle->setFlightMode(rtlFlightMode);
}

void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
    vehicle->setFlightMode(landingFlightMode);
}

void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
{
    Q_UNUSED(altitudeRel);
    if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
        qgcApp()->showMessage(QStringLiteral("Unable to takeoff, vehicle position not known."));
        return;
    }

301
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
302

303
    // Set destination altitude
304
    mavlink_message_t msg;
Lorenz Meier's avatar
Lorenz Meier committed
305
    mavlink_command_long_t cmd;
306

Lorenz Meier's avatar
Lorenz Meier committed
307
    cmd.command = (uint16_t)MAV_CMD_NAV_TAKEOFF;
308
    cmd.confirmation = 0;
309
    cmd.param1 = -1.0f;
310
    cmd.param2 = 0.0f;
311
    cmd.param3 = 0.0f;
312 313 314 315
    cmd.param4 = NAN;
    cmd.param5 = NAN;
    cmd.param6 = NAN;
    cmd.param7 = vehicle->altitudeAMSL()->rawValue().toDouble() + altitudeRel;
316 317 318
    cmd.target_system = vehicle->id();
    cmd.target_component = 0;

319
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);
320 321 322 323 324 325 326 327 328 329 330
    vehicle->sendMessage(msg);
}

void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
    if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
        qgcApp()->showMessage(QStringLiteral("Unable to go to location, vehicle position not known."));
        return;
    }

    mavlink_message_t msg;
Lorenz Meier's avatar
Lorenz Meier committed
331
    mavlink_command_long_t cmd;
332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358

    cmd.command = (uint16_t)MAV_CMD_DO_REPOSITION;
    cmd.confirmation = 0;
    cmd.param1 = -1.0f;
    cmd.param2 = MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
    cmd.param3 = 0.0f;
    cmd.param4 = NAN;
    cmd.param5 = gotoCoord.latitude() * 1e7;
    cmd.param6 = gotoCoord.longitude() * 1e7;
    cmd.param7 = vehicle->altitudeAMSL()->rawValue().toDouble();
    cmd.target_system = vehicle->id();
    cmd.target_component = 0;

    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);

    vehicle->sendMessage(msg);
}

void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel)
{
    if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
        qgcApp()->showMessage(QStringLiteral("Unable to change altitude, vehicle altitude not known."));
        return;
    }

    mavlink_message_t msg;
Lorenz Meier's avatar
Lorenz Meier committed
359
    mavlink_command_long_t cmd;
360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381

    cmd.command = (uint16_t)MAV_CMD_DO_REPOSITION;
    cmd.confirmation = 0;
    cmd.param1 = -1.0f;
    cmd.param2 = MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
    cmd.param3 = 0.0f;
    cmd.param4 = NAN;
    cmd.param5 = NAN;
    cmd.param6 = NAN;
    cmd.param7 = vehicle->altitudeAMSL()->rawValue().toDouble() + altitudeRel;
    cmd.target_system = vehicle->id();
    cmd.target_component = 0;

    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd);

    vehicle->sendMessage(msg);
}

void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
    if (guidedMode) {
382
        vehicle->setFlightMode(pauseFlightMode);
383 384 385 386
    } else {
        pauseVehicle(vehicle);
    }
}
387 388 389 390

bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
    // Not supported by generic vehicle
391 392
    return (vehicle->flightMode() == pauseFlightMode || vehicle->flightMode() == takeoffFlightMode
            || vehicle->flightMode() == landingFlightMode);
393
}