Commit 3101261e authored by Don Gagne's avatar Don Gagne
Browse files

Merge pull request #1520 from DonLakeFlyer/SimulateGone

Remove the "Simulate" feature
parents 5ae769a1 69712e32
...@@ -235,10 +235,8 @@ HEADERS += \ ...@@ -235,10 +235,8 @@ HEADERS += \
src/comm/LinkInterface.h \ src/comm/LinkInterface.h \
src/comm/LinkManager.h \ src/comm/LinkManager.h \
src/comm/MAVLinkProtocol.h \ src/comm/MAVLinkProtocol.h \
src/comm/MAVLinkSimulationLink.h \ src/comm/MockLink.h \
src/comm/MAVLinkSimulationMAV.h \ src/comm/MockLinkMissionItemHandler.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSwarmSimulationLink.h \
src/comm/ProtocolInterface.h \ src/comm/ProtocolInterface.h \
src/comm/QGCFlightGearLink.h \ src/comm/QGCFlightGearLink.h \
src/comm/QGCHilLink.h \ src/comm/QGCHilLink.h \
...@@ -357,12 +355,6 @@ HEADERS += \ ...@@ -357,12 +355,6 @@ HEADERS += \
src/ViewWidgets/ViewWidgetController.h \ src/ViewWidgets/ViewWidgetController.h \
src/Waypoint.h \ src/Waypoint.h \
DebugBuild {
HEADERS += \
src/comm/MockLink.h \
src/comm/MockLinkMissionItemHandler.h
}
!AndroidBuild { !AndroidBuild {
HEADERS += \ HEADERS += \
src/input/JoystickInput.h \ src/input/JoystickInput.h \
...@@ -378,10 +370,8 @@ SOURCES += \ ...@@ -378,10 +370,8 @@ SOURCES += \
src/comm/LinkConfiguration.cc \ src/comm/LinkConfiguration.cc \
src/comm/LinkManager.cc \ src/comm/LinkManager.cc \
src/comm/MAVLinkProtocol.cc \ src/comm/MAVLinkProtocol.cc \
src/comm/MAVLinkSimulationLink.cc \ src/comm/MockLink.cc \
src/comm/MAVLinkSimulationMAV.cc \ src/comm/MockLinkMissionItemHandler.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
src/comm/QGCFlightGearLink.cc \ src/comm/QGCFlightGearLink.cc \
src/comm/QGCJSBSimLink.cc \ src/comm/QGCJSBSimLink.cc \
src/comm/QGCXPlaneLink.cc \ src/comm/QGCXPlaneLink.cc \
...@@ -492,12 +482,6 @@ SOURCES += \ ...@@ -492,12 +482,6 @@ SOURCES += \
src/ViewWidgets/ViewWidgetController.cc \ src/ViewWidgets/ViewWidgetController.cc \
src/Waypoint.cc \ src/Waypoint.cc \
DebugBuild {
SOURCES += \
src/comm/MockLink.cc \
src/comm/MockLinkMissionItemHandler.cc
}
!AndroidBuild { !AndroidBuild {
SOURCES += \ SOURCES += \
src/input/JoystickInput.cc \ src/input/JoystickInput.cc \
......
...@@ -49,7 +49,6 @@ ...@@ -49,7 +49,6 @@
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "UDPLink.h" #include "UDPLink.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h" #include "SerialLink.h"
#include "QGCSingleton.h" #include "QGCSingleton.h"
#include "LinkManager.h" #include "LinkManager.h"
......
...@@ -44,14 +44,11 @@ public: ...@@ -44,14 +44,11 @@ public:
TypeTcp, ///< TCP Link TypeTcp, ///< TCP Link
// TODO Below is not yet implemented // TODO Below is not yet implemented
#if 0 #if 0
TypeSimulation, ///< Simulation Link
TypeForwarding, ///< Forwarding Link TypeForwarding, ///< Forwarding Link
TypeXbee, ///< XBee Proprietary Link TypeXbee, ///< XBee Proprietary Link
TypeOpal, ///< Opal-RT Link TypeOpal, ///< Opal-RT Link
#endif #endif
#ifdef QT_DEBUG
TypeMock, ///< Mock Link for Unitesting TypeMock, ///< Mock Link for Unitesting
#endif
TypeLast // Last type value (type >= TypeLast == invalid) TypeLast // Last type value (type >= TypeLast == invalid)
}; };
......
This diff is collapsed.
/*=====================================================================
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/>.
======================================================================*/
/**
* @file
* @brief Definition of MAVLinkSimulationLink
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef MAVLINKSIMULATIONLINK_H
#define MAVLINKSIMULATIONLINK_H
#include <QFile>
#include <QTimer>
#include <QTextStream>
#include <QQueue>
#include <QMutex>
#include <QMap>
#include <qmath.h>
#include <inttypes.h>
#include "QGCMAVLink.h"
#include "LinkInterface.h"
class MAVLinkSimulationLink : public LinkInterface
{
Q_OBJECT
public:
MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5);
~MAVLinkSimulationLink();
bool isConnected() const;
void run();
void requestReset() { }
// Extensive statistics for scientific purposes
qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const;
QString getName() const;
int getBaudRate() const;
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void);
bool disconnect(void);
public slots:
void writeBytes(const char* data, qint64 size);
void readBytes();
/** @brief Mainloop simulating the mainloop of the MAV */
virtual void mainloop();
void sendMAVLinkMessage(const mavlink_message_t* msg);
protected:
// UAS properties
float roll, pitch, yaw;
double x, y, z;
double spX, spY, spZ, spYaw;
int battery;
QTimer* timer;
/** File which contains the input data (simulated robot messages) **/
QFile* simulationFile;
QFile* mavlinkLogFile;
QString simulationHeader;
/** File where the commands sent by the groundstation are stored **/
QFile* receiveFile;
QTextStream textStream;
QTextStream* fileStream;
QTextStream* outStream;
/** Buffer which can be read from connected protocols through readBytes(). **/
QMutex readyBufferMutex;
bool _isConnected;
quint64 rate;
int maxTimeNoise;
quint64 lastSent;
static const int streamlength = 4096;
unsigned int streampointer;
//const int testoffset = 0;
uint8_t stream[streamlength];
int readyBytes;
QQueue<uint8_t> readyBuffer;
QString name;
qint64 timeOffset;
mavlink_sys_status_t status;
mavlink_heartbeat_t system;
QMap<QString, float> onboardParams;
void enqueue(uint8_t* stream, uint8_t* index, mavlink_message_t* msg);
static const uint8_t systemId = 220;
static const uint8_t componentId = 200;
static const uint16_t version = 1000;
signals:
void valueChanged(int uasId, QString curve, double value, quint64 usec);
void messageReceived(const mavlink_message_t& message);
private:
// From LinkInterface
virtual bool _connect(void);
virtual bool _disconnect(void);
};
#endif // MAVLINKSIMULATIONLINK_H
#include <QDebug>
#include <cmath>
#include <qmath.h>
#include <QGC.h>
#include "MAVLinkSimulationMAV.h"
MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat, double lon, int version) :
QObject(parent),
link(parent),
planner(parent, systemid),
systemid(systemid),
timer25Hz(0),
timer10Hz(0),
timer1Hz(0),
latitude(lat),
longitude(lon),
altitude(550.0),
x(lat),
y(lon),
z(altitude),
roll(0.0),
pitch(0.0),
yaw(0.0),
rollspeed(0.0),
pitchspeed(0.0),
yawspeed(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),
previousSPX(37.480391),
previousSPY(122.282883),
previousSPZ(550),
previousSPYaw(0.0),
nextSPX(37.480391),
nextSPY(122.282883),
nextSPZ(550),
nextSPYaw(0.0),
sys_mode(MAV_MODE_PREFLIGHT),
sys_state(MAV_STATE_STANDBY),
nav_mode(0),
flying(false),
mavlink_version(version)
{
// Please note: The waypoint planner is running
connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop()));
connect(&planner, SIGNAL(messageSent(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
connect(link, SIGNAL(messageReceived(mavlink_message_t)), this, SLOT(handleMessage(mavlink_message_t)));
mainloopTimer.start(20);
mainloop();
}
void MAVLinkSimulationMAV::mainloop()
{
// Calculate new simulator values
// double maxSpeed = 0.0001; // rad/s in earth coordinate frame
// double xNew = // (nextSPX - previousSPX)
if (flying) {
sys_state = MAV_STATE_ACTIVE;
sys_mode = MAV_MODE_AUTO_ARMED;
nav_mode = 0;
}
// 1 Hz execution
if (timer1Hz <= 0) {
mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
mavlink_servo_output_raw_t servos;
servos.time_usec = 0;
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;
servos.port = 1; // set a fake port number
mavlink_msg_servo_output_raw_encode(systemid, MAV_COMP_ID_IMU, &msg, &servos);
link->sendMAVLinkMessage(&msg);
timer1Hz = 50;
}
// 10 Hz execution
if (timer10Hz <= 0) {
double radPer100ms = 0.00006;
double altPer100ms = 0.4;
double xm = (nextSPX - x);
double ym = (nextSPY - y);
double zm = (nextSPZ - z);
float zsign = (zm < 0) ? -1.0f : 1.0f;
if (!(sys_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL))
{
if (!firstWP) {
//float trueyaw = atan2f(xm, ym);
float newYaw = atan2f(ym, xm);
if (fabs(yaw - newYaw) < 90) {
yaw = yaw*0.7 + 0.3*newYaw;
} else {
yaw = newYaw;
}
//qDebug() << "SIMULATION MAV: x:" << xm << "y:" << ym << "z:" << zm << "yaw:" << yaw;
//if (sqrt(xm*xm+ym*ym) > 0.0000001)
if (flying) {
x += cos(yaw)*radPer100ms;
y += sin(yaw)*radPer100ms;
z += altPer100ms*zsign;
}
//if (xm < 0.001) xm
} else {
x = nextSPX;
y = nextSPY;
z = nextSPZ;
firstWP = false;
// qDebug() << "INIT STEP";
}
}
else
{
// FIXME Implement heading and altitude controller
}
// GLOBAL POSITION
mavlink_message_t msg;
mavlink_global_position_int_t pos;
pos.alt = altitude*1000.0;
pos.lat = longitude*1E7;
pos.lon = longitude*1E7;
pos.vx = sin(yaw)*10.0f*100.0f;
pos.vy = 0;
pos.vz = altPer100ms*10.0f*100.0f*zsign*-1.0f;
mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
// ATTITUDE
mavlink_attitude_t attitude;
attitude.time_boot_ms = 0;
attitude.roll = roll;
attitude.pitch = pitch;
attitude.yaw = yaw;
attitude.rollspeed = rollspeed;
attitude.pitchspeed = pitchspeed;
attitude.yawspeed = yawspeed;
mavlink_msg_attitude_encode(systemid, MAV_COMP_ID_IMU, &msg, &attitude);
link->sendMAVLinkMessage(&msg);
// SYSTEM STATUS
mavlink_sys_status_t status;
// Since the simulation outputs global position, attitude and raw pressure we specify that the
// sensors that would be collecting this information are present, enabled and healthy.
status.onboard_control_sensors_present = MAV_SYS_STATUS_SENSOR_3D_GYRO |
MAV_SYS_STATUS_SENSOR_3D_ACCEL |
MAV_SYS_STATUS_SENSOR_3D_MAG |
MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
MAV_SYS_STATUS_SENSOR_GPS;
status.onboard_control_sensors_enabled = status.onboard_control_sensors_present;
status.onboard_control_sensors_health = status.onboard_control_sensors_present;
status.load = 300;
status.voltage_battery = 10500;
status.current_battery = -1; // -1: autopilot does not measure the current
status.drop_rate_comm = 0;
status.errors_comm = 0;
status.errors_count1 = 0;
status.errors_count2 = 0;
status.errors_count3 = 0;
status.errors_count4 = 0;
status.battery_remaining = 90;
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg);
timer10Hz = 5;
// VFR HUD
mavlink_vfr_hud_t hud;
hud.airspeed = pos.vx/100.0f;
hud.groundspeed = pos.vx/100.0f;
hud.alt = altitude;
hud.heading = static_cast<int>((yaw/M_PI)*180.0f+180.0f) % 360;
hud.climb = pos.vz/100.0f;
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;
nav.wp_dist = 2.0f;
nav.alt_error = 0.5f;
nav.xtrack_error = 0.2f;
nav.aspd_error = 0.0f;
mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav);
link->sendMAVLinkMessage(&msg);
// RAW PRESSURE
mavlink_raw_pressure_t pressure;
pressure.press_abs = 1000;
pressure.press_diff1 = 2000;
pressure.press_diff2 = 5000;
pressure.temperature = 18150; // 18.15 deg Celsius
pressure.time_usec = 0; // Works also with zero timestamp
mavlink_msg_raw_pressure_encode(systemid, MAV_COMP_ID_IMU, &msg, &pressure);
link->sendMAVLinkMessage(&msg);
}
// 25 Hz execution
if (timer25Hz <= 0) {
// The message container to be used for sending
mavlink_message_t ret;
if (sys_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL)
{
mavlink_hil_controls_t hil;
hil.roll_ailerons = 0.0f;
hil.pitch_elevator = 0.05f;
hil.yaw_rudder = 0.05f;
hil.throttle = 0.6f;
hil.aux1 = 0.0f;
hil.aux2 = 0.0f;
hil.aux3 = 0.0f;
hil.aux4 = 0.0f;
hil.mode = MAV_MODE_FLAG_HIL_ENABLED;
hil.nav_mode = 0; // not currently used by any HIL consumers
// Encode the data (adding header and checksums, etc.)
mavlink_msg_hil_controls_encode(systemid, MAV_COMP_ID_IMU, &ret, &hil);
// And send it
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);
// Send a named value with name "FLOAT" and 0.5f as value
// The message container to be used for sending
//mavlink_message_t ret;
// 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/
strcpy((char *)val.name, "FLOAT");
// 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/
strcpy((char *)valint.name, "INTEGER");
// 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);
timer25Hz = 2;
}
timer1Hz--;
timer10Hz--;
timer25Hz--;
}
// Uncomment to turn on debug message printing
//#define DEBUG_PRINT_MESSAGE
#ifdef DEBUG_PRINT_MESSAGE
//static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
//static unsigned error_count;
mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
static void print_one_field(const mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
{
#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def)
switch (f->type) {
case MAVLINK_TYPE_CHAR:
qDebug(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT8_T:
qDebug(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_INT8_T:
qDebug(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1));
break;
case MAVLINK_TYPE_UINT16_T:
qDebug(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_INT16_T:
qDebug(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2));
break;
case MAVLINK_TYPE_UINT32_T:
qDebug(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_INT32_T:
qDebug(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_UINT64_T:
qDebug(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_INT64_T:
qDebug(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8));
break;
case MAVLINK_TYPE_FLOAT:
qDebug(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4));
break;
case MAVLINK_TYPE_DOUBLE:
qDebug(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8));
break;
}
}
static void print_field(const mavlink_message_t *msg, const mavlink_field_info_t *f)
{
qDebug("%s: ", f->name);
if (f->array_length == 0) {
print_one_field(msg, f, 0);
qDebug(" ");
} else {
unsigned i;
/* print an array */
if (f->type == MAVLINK_TYPE_CHAR) {
qDebug("'%.*s'", f->array_length,
f->wire_offset+(const char *)_MAV_PAYLOAD(msg));
} else {
qDebug("[ ");
for (i=0; i<f->array_length; i++) {
print_one_field(msg, f, i);
if (i < f->array_length) {
qDebug(", ");
}
}
qDebug("]");
}
}
qDebug(" ");
}
#endif
static void print_message(const mavlink_message_t *msg)
{
#ifdef DEBUG_PRINT_MESSAGE
const mavlink_message_info_t *m = &message_info[msg->msgid];
const mavlink_field_info_t *f = m->fields;
unsigned i;
qDebug("%s { ", m->name);
for (i=0; i<m->num_fields; i++) {
print_field(msg, &f[i]);
}
qDebug("}\n");
#else
Q_UNUSED(msg);
#endif
}
void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
{
if (msg.sysid != systemid)
{
print_message(&msg);
// qDebug() << "MAV:" << systemid << "RECEIVED MESSAGE FROM" << msg.sysid << "COMP" << msg.compid;
}
switch(msg.msgid) {
case MAVLINK_MSG_ID_ATTITUDE:
break;
case MAVLINK_MSG_ID_SET_MODE: {
mavlink_set_mode_t mode;
mavlink_msg_set_mode_decode(&msg, &mode);
if (systemid == mode.target_system) sys_mode = mode.base_mode;
}
break;
case MAVLINK_MSG_ID_HIL_STATE_QUATERNION:
{
mavlink_hil_state_quaternion_t state;
mavlink_msg_hil_state_quaternion_decode(&msg, &state);
double a = state.attitude_quaternion[0];
double b = state.attitude_quaternion[1];
double c = state.attitude_quaternion[2];
double d = state.attitude_quaternion[3];
double aSq = a * a;
double bSq = b * b;
double cSq = c * c;
double dSq = d * d;
float dcm[3][3];
dcm[0][0] = aSq + bSq - cSq - dSq;
dcm[0][1] = 2.0 * (b * c - a * d);
dcm[0][2] = 2.0 * (a * c + b * d);
dcm[1][0] = 2.0 * (b * c + a * d);
dcm[1][1] = aSq - bSq + cSq - dSq;
dcm[1][2] = 2.0 * (c * d - a * b);
dcm[2][0] = 2.0 * (b * d - a * c);
dcm[2][1] = 2.0 * (a * b + c * d);
dcm[2][2] = aSq - bSq - cSq + dSq;
float phi, theta, psi;
theta = asin(-dcm[2][0]);
if (fabs(theta - M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = (atan2(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1]) + phi);
} else if (fabs(theta + M_PI_2) < 1.0e-3f) {
phi = 0.0f;
psi = atan2f(dcm[1][2] - dcm[0][1],
dcm[0][2] + dcm[1][1] - phi);
} else {
phi = atan2f(dcm[2][1], dcm[2][2]);
psi = atan2f(dcm[1][0], dcm[0][0]);
}
roll = phi;
pitch = theta;
yaw = psi;
rollspeed = state.rollspeed;
pitchspeed = state.pitchspeed;
yawspeed = state.yawspeed;
latitude = state.lat;
longitude = state.lon;
altitude = state.alt;
}
break;
// FIXME MAVLINKV10PORTINGNEEDED
// 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)) {
// mavlink_action_ack_t ack;
// ack.action = action.action;
//// switch (action.action) {
//// case MAV_ACTION_TAKEOFF:
//// flying = true;
//// nav_mode = MAV_NAV_LIFTOFF;
//// ack.result = 1;
//// break;
//// default: {
//// ack.result = 0;
//// }
//// break;
//// }
// // Give feedback about action
// mavlink_message_t r_msg;
// mavlink_msg_action_ack_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &ack);
// link->sendMAVLinkMessage(&r_msg);
// }
// }
break;
}
}
#ifndef MAVLINKSIMULATIONMAV_H
#define MAVLINKSIMULATIONMAV_H
#include <QObject>
#include <QTimer>
#include "MAVLinkSimulationLink.h"
#include "MAVLinkSimulationWaypointPlanner.h"
class MAVLinkSimulationMAV : public QObject
{
Q_OBJECT
public:
explicit MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat=47.376389, double lon=8.548056, int version=MAVLINK_VERSION);
signals:
public slots:
void mainloop();
void handleMessage(const mavlink_message_t& msg);
protected:
MAVLinkSimulationLink* link;
MAVLinkSimulationWaypointPlanner planner;
int systemid;
QTimer mainloopTimer;
int timer25Hz;
int timer10Hz;
int timer1Hz;
double latitude;
double longitude;
double altitude;
double x;
double y;
double z;
double roll;
double pitch;
double yaw;
double rollspeed;
double pitchspeed;
double yawspeed;
bool globalNavigation;
bool firstWP;
double previousSPX;
double previousSPY;
double previousSPZ;
double previousSPYaw;
double nextSPX;
double nextSPY;
double nextSPZ;
double nextSPYaw;
uint8_t sys_mode;
uint8_t sys_state;
uint8_t nav_mode;
bool flying;
int mavlink_version;
// FIXME MAVLINKV10PORTINGNEEDED
// static inline uint16_t mavlink_msg_heartbeat_pack_version_free(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot, uint8_t version) {
// uint16_t i = 0;
// msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
// i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
// i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
// i += put_uint8_t_by_index(version, i, msg->payload); // MAVLink version
// return mavlink_finalize_message(msg, system_id, component_id, i);
// }
};
#endif // MAVLINKSIMULATIONMAV_H
This diff is collapsed.
#ifndef MAVLINKSIMULATIONWAYPOINTPLANNER_H
#define MAVLINKSIMULATIONWAYPOINTPLANNER_H
#include <QObject>
#include <vector>
#include "MAVLinkSimulationLink.h"
#include "QGCMAVLink.h"
enum PX_WAYPOINTPLANNER_STATES {
PX_WPP_IDLE = 0,
PX_WPP_SENDLIST,
PX_WPP_SENDLIST_SENDWPS,
PX_WPP_GETLIST,
PX_WPP_GETLIST_GETWPS,
PX_WPP_GETLIST_GOTALL
};
class MAVLinkSimulationWaypointPlanner : public QObject
{
Q_OBJECT
public:
explicit MAVLinkSimulationWaypointPlanner(MAVLinkSimulationLink *parent, int systemid);
signals:
void messageSent(const mavlink_message_t& msg);
public slots:
void handleMessage(const mavlink_message_t& msg);
protected:
MAVLinkSimulationLink* link;
bool idle; ///< indicates if the system is following the waypoints or is waiting
uint16_t current_active_wp_id; ///< id of current waypoint
bool yawReached; ///< boolean for yaw attitude reached
bool posReached; ///< boolean for position reached
uint64_t timestamp_lastoutside_orbit;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
uint64_t timestamp_firstinside_orbit;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
std::vector<mavlink_mission_item_t*> waypoints1; ///< vector1 that holds the waypoints
std::vector<mavlink_mission_item_t*> waypoints2; ///< vector2 that holds the waypoints
std::vector<mavlink_mission_item_t*>* waypoints; ///< pointer to the currently active waypoint vector
std::vector<mavlink_mission_item_t*>* waypoints_receive_buffer; ///< pointer to the receive buffer waypoint vector
PX_WAYPOINTPLANNER_STATES current_state;
uint16_t protocol_current_wp_id;
uint16_t protocol_current_count;
uint8_t protocol_current_partner_systemid;
uint8_t protocol_current_partner_compid;
uint64_t protocol_timestamp_lastaction;
unsigned int protocol_timeout;
uint64_t timestamp_last_send_setpoint;
uint8_t systemid;
uint8_t compid;
unsigned int setpointDelay;
float yawTolerance;
bool verbose;
bool debug;
bool silent;
void send_waypoint_ack(uint8_t target_systemid, uint8_t target_compid, uint8_t type);
void send_waypoint_current(uint16_t seq);
void send_setpoint(uint16_t seq);
void send_waypoint_count(uint8_t target_systemid, uint8_t target_compid, uint16_t count);
void send_waypoint(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_request(uint8_t target_systemid, uint8_t target_compid, uint16_t seq);
void send_waypoint_reached(uint16_t seq);
float distanceToSegment(uint16_t seq, float x, float y, float z);
float distanceToPoint(uint16_t seq, float x, float y, float z);
float distanceToPoint(uint16_t seq, float x, float y);
void mavlink_handler(const mavlink_message_t* msg);
};
#endif // MAVLINKSIMULATIONWAYPOINTPLANNER_H
#include "MAVLinkSwarmSimulationLink.h"
MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QString readFile, QString writeFile, int rate) :
MAVLinkSimulationLink(readFile, writeFile, rate)
{
}
void MAVLinkSwarmSimulationLink::mainloop()
{
}
#ifndef MAVLINKSWARMSIMULATIONLINK_H
#define MAVLINKSWARMSIMULATIONLINK_H
#include "MAVLinkSimulationLink.h"
class MAVLinkSwarmSimulationLink : public MAVLinkSimulationLink
{
Q_OBJECT
public:
MAVLinkSwarmSimulationLink(QString readFile="", QString writeFile="", int rate=5);
signals:
public slots:
void mainloop();
};
#endif // MAVLINKSWARMSIMULATIONLINK_H
...@@ -29,7 +29,6 @@ ...@@ -29,7 +29,6 @@
#include <QObject> #include <QObject>
#include <vector> #include <vector>
#include "MAVLinkSimulationLink.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
/* Alreedy defined in MAVLinkSimulationLink.h above! /* Alreedy defined in MAVLinkSimulationLink.h above!
......
...@@ -40,7 +40,6 @@ This file is part of the QGROUNDCONTROL project ...@@ -40,7 +40,6 @@ This file is part of the QGROUNDCONTROL project
#include <QDesktopWidget> #include <QDesktopWidget>
#include "QGC.h" #include "QGC.h"
#include "MAVLinkSimulationLink.h"
#include "SerialLink.h" #include "SerialLink.h"
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "QGCWaypointListMulti.h" #include "QGCWaypointListMulti.h"
...@@ -149,7 +148,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) ...@@ -149,7 +148,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen)
, _lowPowerMode(false) , _lowPowerMode(false)
, _showStatusBar(false) , _showStatusBar(false)
, _centerStackActionGroup(new QActionGroup(this)) , _centerStackActionGroup(new QActionGroup(this))
, _simulationLink(NULL)
, _centralLayout(NULL) , _centralLayout(NULL)
, _currentViewWidget(NULL) , _currentViewWidget(NULL)
, _splashScreen(splashScreen) , _splashScreen(splashScreen)
...@@ -346,11 +344,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen) ...@@ -346,11 +344,6 @@ MainWindow::MainWindow(QSplashScreen* splashScreen)
MainWindow::~MainWindow() MainWindow::~MainWindow()
{ {
if (_simulationLink)
{
delete _simulationLink;
_simulationLink = NULL;
}
#ifndef __android__ #ifndef __android__
if (joystick) if (joystick)
{ {
...@@ -857,8 +850,6 @@ void MainWindow::connectCommonActions() ...@@ -857,8 +850,6 @@ void MainWindow::connectCommonActions()
// Application Settings // Application Settings
connect(_ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings())); connect(_ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings()));
connect(_ui.actionSimulate, SIGNAL(triggered(bool)), this, SLOT(simulateLink(bool)));
// Update Tool Bar // Update Tool Bar
_mainToolBar->setCurrentView(_currentView); _mainToolBar->setCurrentView(_currentView);
} }
...@@ -904,19 +895,6 @@ void MainWindow::showSettings() ...@@ -904,19 +895,6 @@ void MainWindow::showSettings()
settings.exec(); settings.exec();
} }
void MainWindow::simulateLink(bool simulate) {
if (simulate) {
if (!_simulationLink) {
_simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
Q_CHECK_PTR(_simulationLink);
}
LinkManager::instance()->connectLink(_simulationLink);
} else {
Q_ASSERT(_simulationLink);
LinkManager::instance()->disconnectLink(_simulationLink);
}
}
void MainWindow::commsWidgetDestroyed(QObject *obj) void MainWindow::commsWidgetDestroyed(QObject *obj)
{ {
// Do not dynamic cast or de-reference QObject, since object is either in destructor or may have already // Do not dynamic cast or de-reference QObject, since object is either in destructor or may have already
......
...@@ -47,7 +47,6 @@ This file is part of the QGROUNDCONTROL project ...@@ -47,7 +47,6 @@ This file is part of the QGROUNDCONTROL project
#include "WaypointList.h" #include "WaypointList.h"
#include "CameraView.h" #include "CameraView.h"
#include "UASListWidget.h" #include "UASListWidget.h"
#include "MAVLinkSimulationLink.h"
#ifndef __android__ #ifndef __android__
#include "input/JoystickInput.h" #include "input/JoystickInput.h"
#endif #endif
...@@ -145,8 +144,6 @@ public: ...@@ -145,8 +144,6 @@ public:
public slots: public slots:
/** @brief Show the application settings */ /** @brief Show the application settings */
void showSettings(); void showSettings();
/** @brief Simulate a link */
void simulateLink(bool simulate);
/** @brief Add a new UAS */ /** @brief Add a new UAS */
void UASCreated(UASInterface* uas); void UASCreated(UASInterface* uas);
...@@ -292,7 +289,6 @@ protected: ...@@ -292,7 +289,6 @@ protected:
QAction* returnUASAct; QAction* returnUASAct;
QAction* stopUASAct; QAction* stopUASAct;
QAction* killUASAct; QAction* killUASAct;
QAction* simulateUASAct;
LogCompressor* comp; LogCompressor* comp;
...@@ -366,7 +362,6 @@ private: ...@@ -366,7 +362,6 @@ private:
bool _lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets bool _lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
bool _showStatusBar; bool _showStatusBar;
QActionGroup* _centerStackActionGroup; QActionGroup* _centerStackActionGroup;
MAVLinkSimulationLink* _simulationLink;
QVBoxLayout* _centralLayout; QVBoxLayout* _centralLayout;
QList<QObject*> _commsWidgetList; QList<QObject*> _commsWidgetList;
QWidget* _currentViewWidget; ///< Currently displayed view widget QWidget* _currentViewWidget; ///< Currently displayed view widget
......
...@@ -101,7 +101,6 @@ ...@@ -101,7 +101,6 @@
<addaction name="actionTerminalView"/> <addaction name="actionTerminalView"/>
<addaction name="actionSimulationView"/> <addaction name="actionSimulationView"/>
<addaction name="separator"/> <addaction name="separator"/>
<addaction name="actionSimulate"/>
<addaction name="separator"/> <addaction name="separator"/>
<addaction name="menuTools"/> <addaction name="menuTools"/>
</widget> </widget>
...@@ -170,17 +169,6 @@ ...@@ -170,17 +169,6 @@
<string>Manage Communication Links</string> <string>Manage Communication Links</string>
</property> </property>
</action> </action>
<action name="actionSimulate">
<property name="checkable">
<bool>true</bool>
</property>
<property name="text">
<string>Simulate</string>
</property>
<property name="toolTip">
<string>Simulate one vehicle to test and evaluate this application</string>
</property>
</action>
<action name="actionOnline_Documentation"> <action name="actionOnline_Documentation">
<property name="text"> <property name="text">
<string>Online Documentation</string> <string>Online Documentation</string>
......
...@@ -317,7 +317,8 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file) ...@@ -317,7 +317,8 @@ bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
if (logLink) { if (logLink) {
LinkManager::instance()->_deleteLink(logLink); LinkManager::instance()->_deleteLink(logLink);
} }
logLink = new MAVLinkSimulationLink(""); logLink = new MockLink();
LinkManager::instance()->_addLink(logLink);
// Select if binary or MAVLink log format is used // Select if binary or MAVLink log format is used
mavlinkLogFormat = file.endsWith(".mavlink"); mavlinkLogFormat = file.endsWith(".mavlink");
......
...@@ -6,7 +6,7 @@ ...@@ -6,7 +6,7 @@
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "LinkInterface.h" #include "LinkInterface.h"
#include "MAVLinkSimulationLink.h" #include "MockLink.h"
namespace Ui namespace Ui
{ {
...@@ -67,7 +67,7 @@ protected: ...@@ -67,7 +67,7 @@ protected:
quint64 logEndTime; ///< The last timestamp in the current log file. In units of microseconds since epoch UTC. quint64 logEndTime; ///< The last timestamp in the current log file. In units of microseconds since epoch UTC.
float accelerationFactor; float accelerationFactor;
MAVLinkProtocol* mavlink; MAVLinkProtocol* mavlink;
MAVLinkSimulationLink* logLink; MockLink* logLink;
QFile logFile; QFile logFile;
QTimer loopTimer; QTimer loopTimer;
int loopCounter; int loopCounter;
......
#include "QGCUnconnectedInfoWidget.h" #include "QGCUnconnectedInfoWidget.h"
#include "LinkInterface.h" #include "LinkInterface.h"
#include "LinkManager.h" #include "LinkManager.h"
#include "MAVLinkSimulationLink.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "ui_QGCUnconnectedInfoWidget.h" #include "ui_QGCUnconnectedInfoWidget.h"
...@@ -24,15 +23,6 @@ QGCUnconnectedInfoWidget::~QGCUnconnectedInfoWidget() ...@@ -24,15 +23,6 @@ QGCUnconnectedInfoWidget::~QGCUnconnectedInfoWidget()
*/ */
void QGCUnconnectedInfoWidget::simulate() void QGCUnconnectedInfoWidget::simulate()
{ {
// TODO What is this?
// Try to get reference to MAVLinkSimulationlink
QList<LinkInterface*> links = LinkManager::instance()->getLinks();
foreach(LinkInterface* link, links) {
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim) {
LinkManager::instance()->connectLink(sim);
}
}
} }
/** /**
......
...@@ -41,7 +41,6 @@ This file is part of the PIXHAWK project ...@@ -41,7 +41,6 @@ This file is part of the PIXHAWK project
#include "UASView.h" #include "UASView.h"
#include "QGCUnconnectedInfoWidget.h" #include "QGCUnconnectedInfoWidget.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "MAVLinkSimulationLink.h"
#include "LinkManager.h" #include "LinkManager.h"
UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent), UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent),
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment