Skip to content
MockLink.cc 38 KiB
Newer Older
    mockConfig->setFirmwareType(MAV_AUTOPILOT_GENERIC);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
    mockConfig->setFailureMode(failureMode);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
MockLink*  MockLink::startAPMArduCopterMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduCopter MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_QUADROTOR);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
    mockConfig->setFailureMode(failureMode);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
MockLink*  MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfiguration::FailureMode_t failureMode)
{
    MockConfiguration* mockConfig = new MockConfiguration("APM ArduPlane MockLink");

    mockConfig->setFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
    mockConfig->setVehicleType(MAV_TYPE_FIXED_WING);
    mockConfig->setSendStatusText(sendStatusText);
Don Gagne's avatar
Don Gagne committed
    mockConfig->setFailureMode(failureMode);

    return _startMockLink(mockConfig);
}

Don Gagne's avatar
Don Gagne committed
void MockLink::_sendRCChannels(void)
{
    mavlink_message_t   msg;

    mavlink_msg_rc_channels_pack(_vehicleSystemId,
                                 _vehicleComponentId,
                                 &msg,
                                 0,                     // time_boot_ms
                                 8,                     // chancount
                                 1500,                  // chan1_raw
                                 1500,                  // chan2_raw
                                 1500,                  // chan3_raw
                                 1500,                  // chan4_raw
                                 1500,                  // chan5_raw
                                 1500,                  // chan6_raw
                                 1500,                  // chan7_raw
                                 1500,                  // chan8_raw
                                 UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
                                 0);                    // rssi

    respondWithMavlinkMessage(msg);

}

void MockLink::_handlePreFlightCalibration(const mavlink_command_long_t& request)
{
    const char* pCalMessage;
    static const char* gyroCalResponse = "[cal] calibration started: 2 gyro";
    static const char* magCalResponse = "[cal] calibration started: 2 mag";
    static const char* accelCalResponse = "[cal] calibration started: 2 accel";

    if (request.param1 == 1) {
        // Gyro cal
        pCalMessage = gyroCalResponse;
    } else if (request.param2 == 1) {
        // Mag cal
        pCalMessage = magCalResponse;
    } else if (request.param5 == 1) {
        // Accel cal
        pCalMessage = accelCalResponse;
    } else {
        return;
    }

    mavlink_message_t msg;
    mavlink_msg_statustext_pack(_vehicleSystemId,
                                _vehicleComponentId,
                                &msg,
                                MAV_SEVERITY_INFO,
                                pCalMessage);
    respondWithMavlinkMessage(msg);
}