MAVLinkSimulationMAV.cc 10.6 KB
Newer Older
1
#include <QDebug>
2
#include <cmath>
pixhawk's avatar
pixhawk committed
3
#include <qmath.h>
4 5 6

#include "MAVLinkSimulationMAV.h"

7
MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat, double lon) :
8 9 10 11 12 13 14
        QObject(parent),
        link(parent),
        planner(parent, systemid),
        systemid(systemid),
        timer25Hz(0),
        timer10Hz(0),
        timer1Hz(0),
15 16
        latitude(lat),
        longitude(lon),
17
        altitude(0.0),
18 19
        x(lon),
        y(lat),
20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37
        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)
38
{
39
    // Please note: The waypoint planner is running
40
    connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop()));
41
    connect(&planner, SIGNAL(messageSent(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
42
    connect(link, SIGNAL(messageReceived(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
43
    mainloopTimer.start(20);
44 45 46 47 48
    mainloop();
}

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

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

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

61 62 63 64 65 66
    // 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
67
        planner.handleMessage(msg);
68 69 70 71 72 73 74 75 76 77 78 79 80

        mavlink_servo_output_raw_t servos;
        servos.servo1_raw = 1000;
        servos.servo2_raw = 1250;
        servos.servo3_raw = 1400;
        servos.servo4_raw = 1500;
        servos.servo5_raw = 1800;
        servos.servo6_raw = 1500;
        servos.servo7_raw = 1500;
        servos.servo8_raw = 2000;

        mavlink_msg_servo_output_raw_encode(systemid, MAV_COMP_ID_IMU, &msg, &servos);
        link->sendMAVLinkMessage(&msg);
81 82 83 84 85 86
        timer1Hz = 50;
    }

    // 10 Hz execution
    if (timer10Hz <= 0)
    {
pixhawk's avatar
pixhawk committed
87 88 89 90 91
        double radPer100ms = 0.00006;
        double altPer100ms = 0.4;
        double xm = (nextSPX - x);
        double ym = (nextSPY - y);
        double zm = (nextSPZ - z);
pixhawk's avatar
pixhawk committed
92

pixhawk's avatar
pixhawk committed
93
        float zsign = (zm < 0) ? -1.0f : 1.0f;
pixhawk's avatar
pixhawk committed
94

pixhawk's avatar
pixhawk committed
95 96
        if (!firstWP)
        {
pixhawk's avatar
pixhawk committed
97 98
            //float trueyaw = atan2f(xm, ym);

99 100 101 102 103 104 105
            float newYaw = atan2f(xm, ym);

            if (fabs(yaw - newYaw) < 90)
            {
                yaw = yaw*0.7 + 0.3*newYaw;
            }
            else
pixhawk's avatar
pixhawk committed
106
            {
107 108 109 110 111 112 113 114 115 116
                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
117 118 119 120 121 122 123 124 125 126 127 128 129 130 131
                z += altPer100ms*zsign;
            }

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


132
        // GLOBAL POSITION
133 134 135 136 137
        mavlink_message_t msg;
        mavlink_global_position_int_t pos;
        pos.alt = z*1000.0;
        pos.lat = y*1E7;
        pos.lon = x*1E7;
lm's avatar
lm committed
138 139
        pos.vx = 10.0f*100.0f;
        pos.vy = 0;
pixhawk's avatar
pixhawk committed
140
        pos.vz = altPer100ms*10.0f*100.0f*zsign*-1.0f;
141 142
        mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos);
        link->sendMAVLinkMessage(&msg);
pixhawk's avatar
pixhawk committed
143
        planner.handleMessage(msg);
144 145

        // ATTITUDE
pixhawk's avatar
pixhawk committed
146 147 148 149 150 151 152
        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);
153 154 155 156 157 158 159 160 161 162 163

        // SYSTEM STATUS
        mavlink_sys_status_t status;
        status.load = 300;
        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);
164
        link->sendMAVLinkMessage(&msg);
165
        timer10Hz = 5;
166 167 168

        // VFR HUD
        mavlink_vfr_hud_t hud;
lm's avatar
lm committed
169 170 171
        hud.airspeed = pos.vx;
        hud.groundspeed = pos.vx;
        hud.alt = pos.alt;
172
        hud.heading = static_cast<int>((yaw/M_PI)*180.0f+180.0f) % 360;
lm's avatar
lm committed
173
        hud.climb = pos.vz;
174 175 176 177 178 179 180 181 182 183
        hud.throttle = 90;
        mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud);
        link->sendMAVLinkMessage(&msg);

        // NAV CONTROLLER
        mavlink_nav_controller_output_t nav;
        nav.nav_roll = roll;
        nav.nav_pitch = pitch;
        nav.nav_bearing = yaw;
        nav.target_bearing = yaw;
lm's avatar
lm committed
184 185 186
        nav.wp_dist = 2.0f;
        nav.alt_error = 0.5f;
        nav.xtrack_error = 0.2f;
187 188
        mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav);
        link->sendMAVLinkMessage(&msg);
189 190 191 192 193
    }

    // 25 Hz execution
    if (timer25Hz <= 0)
    {
194 195 196
        // The message container to be used for sending
        mavlink_message_t ret;

James Goppert's avatar
James Goppert committed
197
        #ifdef MAVLINK_ENABLED_PIXHAWK
198 199 200 201 202 203
        // 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;
204 205 206
        control_status.gps_fix = 2;        // 2D GPS fix
        control_status.position_fix = 3;   // 3D fix from GPS + barometric pressure
        control_status.vision_fix = 0;     // no fix from vision system
207 208
        mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status);
        link->sendMAVLinkMessage(&ret);
James Goppert's avatar
James Goppert committed
209
        #endif //MAVLINK_ENABLED_PIXHAWK
210 211 212 213

        // Send actual controller outputs
        // This message just shows the direction
        // and magnitude of the control output
214 215 216 217 218 219
//        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
220 221 222 223

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

        // The message container to be used for sending
224
        //mavlink_message_t ret;
pixhawk's avatar
pixhawk committed
225 226 227 228 229 230 231
        // 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
232
        strcpy((char *)val.name, "FLOAT");
pixhawk's avatar
pixhawk committed
233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259
        // 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
260
        strcpy((char *)valint.name, "INTEGER");
pixhawk's avatar
pixhawk committed
261 262 263 264 265 266 267 268 269 270 271 272 273 274
        // 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);

275 276 277 278 279 280
        timer25Hz = 2;
    }

    timer1Hz--;
    timer10Hz--;
    timer25Hz--;
281 282 283 284
}

void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
{
285
    //qDebug() << "MAV:" << systemid << "RECEIVED MESSAGE FROM" << msg.sysid << "COMP" << msg.compid;
286 287 288 289 290

    switch(msg.msgid)
    {
    case MAVLINK_MSG_ID_ATTITUDE:
        break;
291 292 293 294 295 296 297 298 299 300 301 302 303 304 305
    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)
                {
306
                case MAV_ACTION_TAKEOFF:
307 308 309 310 311 312 313 314 315 316 317 318 319 320 321
                    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;
322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338
    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
339
                //yaw = atan2(previousSPX-nextSPX, previousSPY-nextSPY);
340

pixhawk's avatar
pixhawk committed
341
                //if (!firstWP) firstWP = true;
342 343 344 345
            }
            //qDebug() << "UPDATED SP:" << "X" << nextSPX << "Y" << nextSPY << "Z" << nextSPZ;
        }
        break;
346 347
    }
}