MAVLinkSimulationMAV.cc 9.12 KB
Newer Older
1
#include <QDebug>
2
#include <cmath>
3 4 5

#include "MAVLinkSimulationMAV.h"

6
MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat, double lon) :
7 8 9 10 11 12 13
        QObject(parent),
        link(parent),
        planner(parent, systemid),
        systemid(systemid),
        timer25Hz(0),
        timer10Hz(0),
        timer1Hz(0),
14 15
        latitude(lat),
        longitude(lon),
16
        altitude(0.0),
17 18
        x(lon),
        y(lat),
19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36
        z(550),
        roll(0.0),
        pitch(0.0),
        yaw(0.0),
        globalNavigation(true),
        firstWP(false),
        previousSPX(8.548056),
        previousSPY(47.376389),
        previousSPZ(550),
        previousSPYaw(0.0),
        nextSPX(8.548056),
        nextSPY(47.376389),
        nextSPZ(550),
        nextSPYaw(0.0),
        sys_mode(MAV_MODE_READY),
        sys_state(MAV_STATE_STANDBY),
        nav_mode(MAV_NAV_GROUNDED),
        flying(false)
37
{
38
    // Please note: The waypoint planner is running
39
    connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop()));
40
    connect(&planner, SIGNAL(messageSent(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
41
    connect(link, SIGNAL(messageReceived(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
42
    mainloopTimer.start(20);
43 44 45 46 47
    mainloop();
}

void MAVLinkSimulationMAV::mainloop()
{
48
    // Calculate new simulator values
49
    //    double maxSpeed = 0.0001; // rad/s in earth coordinate frame
50

51
    //        double xNew = // (nextSPX - previousSPX)
52

53 54 55 56 57 58 59
    if (flying)
    {
        sys_state = MAV_STATE_ACTIVE;
        sys_mode = MAV_MODE_AUTO;
        nav_mode = MAV_NAV_WAYPOINT;
    }

60 61 62 63 64 65
    // 1 Hz execution
    if (timer1Hz <= 0)
    {
        mavlink_message_t msg;
        mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
        link->sendMAVLinkMessage(&msg);
pixhawk's avatar
pixhawk committed
66
        planner.handleMessage(msg);
67 68 69 70 71 72
        timer1Hz = 50;
    }

    // 10 Hz execution
    if (timer10Hz <= 0)
    {
pixhawk's avatar
pixhawk committed
73 74
        if (!firstWP)
        {
75 76
            double radPer100ms = 0.00006;
            double altPer100ms = 1.0;
pixhawk's avatar
pixhawk committed
77 78 79 80 81 82 83 84
            double xm = (nextSPX - x);
            double ym = (nextSPY - y);
            double zm = (nextSPZ - z);

            float zsign = (zm < 0) ? -1.0f : 1.0f;

            //float trueyaw = atan2f(xm, ym);

85 86 87 88 89 90 91
            float newYaw = atan2f(xm, ym);

            if (fabs(yaw - newYaw) < 90)
            {
                yaw = yaw*0.7 + 0.3*newYaw;
            }
            else
pixhawk's avatar
pixhawk committed
92
            {
93 94 95 96 97 98 99 100 101 102
                yaw = newYaw;
            }

            //qDebug() << "SIMULATION MAV: x:" << xm << "y:" << ym << "z:" << zm << "yaw:" << yaw;

            //if (sqrt(xm*xm+ym*ym) > 0.0000001)
            if (flying)
            {
                x += sin(yaw)*radPer100ms;
                y += cos(yaw)*radPer100ms;
pixhawk's avatar
pixhawk committed
103 104 105 106 107 108 109 110 111 112 113 114 115 116 117
                z += altPer100ms*zsign;
            }

            //if (xm < 0.001) xm
        }
        else
        {
            x = nextSPX;
            y = nextSPY;
            z = nextSPZ;
            firstWP = false;
            qDebug() << "INIT STEP";
        }


118
        // GLOBAL POSITION
119 120 121 122 123 124 125 126 127 128
        mavlink_message_t msg;
        mavlink_global_position_int_t pos;
        pos.alt = z*1000.0;
        pos.lat = y*1E7;
        pos.lon = x*1E7;
        pos.vx = 0;
        pos.vy = 0;
        pos.vz = 0;
        mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos);
        link->sendMAVLinkMessage(&msg);
pixhawk's avatar
pixhawk committed
129
        planner.handleMessage(msg);
130 131

        // ATTITUDE
pixhawk's avatar
pixhawk committed
132 133 134 135 136 137 138
        mavlink_attitude_t attitude;
        attitude.roll = 0.0f;
        attitude.pitch = 0.0f;
        attitude.yaw = yaw;

        mavlink_msg_attitude_encode(systemid, MAV_COMP_ID_IMU, &msg, &attitude);
        link->sendMAVLinkMessage(&msg);
139 140 141 142 143 144 145 146 147 148 149 150

        // SYSTEM STATUS
        mavlink_sys_status_t status;
        status.load = 300;
        status.motor_block = 1;
        status.mode = sys_mode;
        status.nav_mode = nav_mode;
        status.packet_drop = 0;
        status.vbat = 10500;
        status.status = sys_state;

        mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
151
        link->sendMAVLinkMessage(&msg);
152 153 154 155 156 157
        timer10Hz = 5;
    }

    // 25 Hz execution
    if (timer25Hz <= 0)
    {
158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178
        // The message container to be used for sending
        mavlink_message_t ret;

        // Send which controllers are active
        mavlink_control_status_t control_status;
        control_status.control_att = 1;
        control_status.control_pos_xy = 1;
        control_status.control_pos_yaw = 1;
        control_status.control_pos_z = 1;
        mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status);
        link->sendMAVLinkMessage(&ret);

        // Send actual controller outputs
        // This message just shows the direction
        // and magnitude of the control output
        mavlink_position_controller_output_t pos;
        pos.x = sin(yaw)*127.0f;
        pos.y = cos(yaw)*127.0f;
        pos.z = 0;
        mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos);
        link->sendMAVLinkMessage(&ret);
pixhawk's avatar
pixhawk committed
179 180 181 182

        // Send a named value with name "FLOAT" and 0.5f as value

        // The message container to be used for sending
183
        //mavlink_message_t ret;
pixhawk's avatar
pixhawk committed
184 185 186 187 188 189 190
        // The C-struct holding the data to be sent
        mavlink_named_value_float_t val;

        // Fill in the data
        // Name of the value, maximum 10 characters
        // see full message specs at:
        // http://pixhawk.ethz.ch/wiki/mavlink/
Andrew Tridgell's avatar
Andrew Tridgell committed
191
        strcpy((char *)val.name, "FLOAT");
pixhawk's avatar
pixhawk committed
192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
        // Value, in this case 0.5
        val.value = 0.5f;

        // Encode the data (adding header and checksums, etc.)
        mavlink_msg_named_value_float_encode(systemid, MAV_COMP_ID_IMU, &ret, &val);
        // And send it
        link->sendMAVLinkMessage(&ret);

        // MICROCONTROLLER SEND CODE:

        // uint8_t buf[MAVLINK_MAX_PACKET_LEN];
        // int16_t len = mavlink_msg_to_send_buffer(buf, &ret);
        // uart0_transmit(buf, len);


        // SEND INTEGER VALUE

        // We are reusing the "mavlink_message_t ret"
        // message buffer

        // The C-struct holding the data to be sent
        mavlink_named_value_int_t valint;

        // Fill in the data
        // Name of the value, maximum 10 characters
        // see full message specs at:
        // http://pixhawk.ethz.ch/wiki/mavlink/
Andrew Tridgell's avatar
Andrew Tridgell committed
219
        strcpy((char *)valint.name, "INTEGER");
pixhawk's avatar
pixhawk committed
220 221 222 223 224 225 226 227 228 229 230 231 232 233
        // Value, in this case 18000
        valint.value = 18000;

        // Encode the data (adding header and checksums, etc.)
        mavlink_msg_named_value_int_encode(systemid, MAV_COMP_ID_IMU, &ret, &valint);
        // And send it
        link->sendMAVLinkMessage(&ret);

        // MICROCONTROLLER SEND CODE:

        // uint8_t buf[MAVLINK_MAX_PACKET_LEN];
        // int16_t len = mavlink_msg_to_send_buffer(buf, &ret);
        // uart0_transmit(buf, len);

234 235 236 237 238 239
        timer25Hz = 2;
    }

    timer1Hz--;
    timer10Hz--;
    timer25Hz--;
240 241 242 243
}

void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
{
244
    //qDebug() << "MAV:" << systemid << "RECEIVED MESSAGE FROM" << msg.sysid << "COMP" << msg.compid;
245 246 247 248 249

    switch(msg.msgid)
    {
    case MAVLINK_MSG_ID_ATTITUDE:
        break;
250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280
    case MAVLINK_MSG_ID_SET_MODE:
        {
            mavlink_set_mode_t mode;
            mavlink_msg_set_mode_decode(&msg, &mode);
            if (systemid == mode.target) sys_mode = mode.mode;
        }
        break;
    case MAVLINK_MSG_ID_ACTION:
        {
            mavlink_action_t action;
            mavlink_msg_action_decode(&msg, &action);
            if (systemid == action.target && (action.target_component == 0 || action.target_component == MAV_COMP_ID_IMU))
            {
                switch (action.action)
                {
                case MAV_ACTION_LAUNCH:
                    flying = true;
                    break;
                default:
                    {
                        mavlink_statustext_t text;
                        mavlink_message_t r_msg;
                        sprintf((char*)text.text, "MAV%d ignored unknown action %d", systemid, action.action);
                        mavlink_msg_statustext_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &text);
                        link->sendMAVLinkMessage(&r_msg);
                    }
                    break;
                }
            }
        }
        break;
281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297
    case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
        {
            mavlink_local_position_setpoint_set_t sp;
            mavlink_msg_local_position_setpoint_set_decode(&msg, &sp);
            if (sp.target_system == this->systemid)
            {
                previousSPX = nextSPX;
                previousSPY = nextSPY;
                previousSPZ = nextSPZ;
                nextSPX = sp.x;
                nextSPY = sp.y;
                nextSPZ = sp.z;

                // Rotary wing
                //nextSPYaw = sp.yaw;

                // Airplane
pixhawk's avatar
pixhawk committed
298
                //yaw = atan2(previousSPX-nextSPX, previousSPY-nextSPY);
299

pixhawk's avatar
pixhawk committed
300
                //if (!firstWP) firstWP = true;
301 302 303 304
            }
            //qDebug() << "UPDATED SP:" << "X" << nextSPX << "Y" << nextSPY << "Z" << nextSPZ;
        }
        break;
305 306
    }
}