OpalRT.h 3.78 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    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.

    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.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

24 25 26 27 28 29
/**
 * @file
 *   @brief Types used for Opal-RT interface configuration
 *   @author Bryan Godbolt <godbolt@ualberta.ca>
 */

30 31 32
#ifndef OPALRT_H
#define OPALRT_H

33 34 35 36 37
#include <QString>
#include <QMessageBox>

#include "OpalApi.h"

38 39
namespace OpalRT
{
40 41 42 43
    /**
      Configuration info for the model
     */

44
    const unsigned short NUM_OUTPUT_SIGNALS=48;
45

46 47 48 49 50 51 52
    /*  ------------------------------ Outputs ------------------------------
    *
    *      Port 1: Navigation state estimates
    *      1       t   [s]     time elapsed since INS mode started
    *      2-4     p^n [m]     navigation frame position (N,E,D)
    *      5-7     v^n [m/s]   navigation frame velocity (N,E,D)
    *      8-10    Euler angles [rad] (roll, pitch, yaw)
53 54 55
    *     11-13    Angular rates
    *     14-16    b_f [m/s^2] accelerometer biases
    *     17-19    b_w [rad/s] gyro biases
56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79
    *
    *      Port 2: Navigation system status
    *      1       mode    (0: initialization, 1: INS)
    *      2       t_GPS   time elapsed since last valid GPS measurement
    *      3       solution status (0: SOL_COMPUTED, 1: INSUFFICIENT_OBS)
    *      4       position solution type ( 0: NONE, 34: NARROW_FLOAT,
    *                                      49: WIDE_INT, 50: NARROW_INT)
    *      5       # obs (number of visible satellites)
    *
    *      Port 3: Covariance matrix diagonal
    *      1-15    diagonal elements of estimation error covariance matrix P
    */
    enum SignalPort
    {
        T_ELAPSED,
        X_POS,
        Y_POS,
        Z_POS,
        X_VEL,
        Y_VEL,
        Z_VEL,
        ROLL,
        PITCH,
        YAW,
80 81 82
        ROLL_SPEED,
        PITCH_SPEED,
        YAW_SPEED,
83 84 85 86 87
        B_F_0,
        B_F_1,
        B_F_2,
        B_W_0,
        B_W_1,
Bryan Godbolt's avatar
Bryan Godbolt committed
88
        B_W_2,
Bryan Godbolt's avatar
Bryan Godbolt committed
89
        RAW_CHANNEL_1 = 24,
Bryan Godbolt's avatar
Bryan Godbolt committed
90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
        RAW_CHANNEL_2,
        RAW_CHANNEL_3,
        RAW_CHANNEL_4,
        RAW_CHANNEL_5,
        RAW_CHANNEL_6,
        RAW_CHANNEL_7,
        RAW_CHANNEL_8,
        NORM_CHANNEL_1,
        NORM_CHANNEL_2,
        NORM_CHANNEL_3,
        NORM_CHANNEL_4,
        NORM_CHANNEL_5,
        NORM_CHANNEL_6,
        NORM_CHANNEL_7,
        NORM_CHANNEL_8,
        CONTROLLER_AILERON,
106 107 108 109 110 111 112
        CONTROLLER_ELEVATOR,
        AIL_POUT,
        AIL_IOUT,
        AIL_DOUT,
        ELE_POUT,
        ELE_IOUT,
        ELE_DOUT
113
    };       
114

115
    /** Component IDs of the parameters.  Currently they are all 1 becuase there is no advantage
116 117 118
       to dividing them between component ids.  However this syntax is used so that this can
       easily be changed in the future.
       */
119 120
    enum SubsystemIds
    {
121 122 123
        NAV = 1,
        LOG,
        CONTROLLER,
124 125
        SERVO_OUTPUTS,
        SERVO_INPUTS
126
    };
127 128 129 130 131 132 133 134

    class OpalErrorMsg
    {
        static QString lastErrorMsg;
    public:
        static void displayLastErrorMsg();
        static void setLastErrorMsg();
    };
135 136
}
#endif // OPALRT_H