Commit 73829d12 authored by lm's avatar lm

Updated to most recent MAVLink v10 draft

parent 4eec1224
......@@ -396,7 +396,7 @@ void MAVLinkProtocol::sendHeartbeat()
{
if (m_heartbeatsEnabled) {
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_OCU, MAV_CLASS_INVALID);
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_OCU, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL, MAV_FLIGHT_MODE_MANUAL, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
sendMessage(beat);
}
if (m_authEnabled) {
......
......@@ -107,12 +107,11 @@ MAVLinkSimulationLink::~MAVLinkSimulationLink()
void MAVLinkSimulationLink::run()
{
status.mode = MAV_MODE_UNINIT;
status.status = MAV_STATE_UNINIT;
status.vbat = 0;
status.packet_drop = 0;
status.voltage_battery = 0;
status.errors_uart = 0;
system.system_mode = MAV_MODE_PREFLIGHT;
system.system_status = MAV_STATE_UNINIT;
forever {
......@@ -208,14 +207,6 @@ void MAVLinkSimulationLink::mainloop()
static int state = 0;
if (state == 0) {
// BOOT
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_boot_pack(systemId, componentId, &msg, version);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
state++;
}
......@@ -463,7 +454,7 @@ void MAVLinkSimulationLink::mainloop()
// STATE
static int statusCounter = 0;
if (statusCounter == 100) {
status.mode = (status.mode + 1) % MAV_MODE_TEST3;
system.system_mode = (system.system_mode + 1) % MAV_MODE_ENUM_END;
statusCounter = 0;
}
statusCounter++;
......@@ -512,7 +503,7 @@ void MAVLinkSimulationLink::mainloop()
}
detectionCounter++;
status.vbat = voltage * 1000; // millivolts
status.voltage_battery = voltage * 1000; // millivolts
status.load = 33 * detectionCounter % 1000;
// Pack message and get size of encoded byte string
......@@ -553,7 +544,7 @@ void MAVLinkSimulationLink::mainloop()
typeCounter++;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_CLASS_PIXHAWK);
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.system_mode, system.flight_mode, system.system_status, system.safety_status, system.link_status);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
......@@ -606,10 +597,11 @@ void MAVLinkSimulationLink::mainloop()
// STATUS VEHICLE 2
mavlink_sys_status_t status2;
status2.mode = MAV_MODE_LOCKED;
status2.vbat = voltage;
mavlink_heartbeat_t system2;
system2.system_mode = MAV_MODE_PREFLIGHT;
status2.voltage_battery = voltage;
status2.load = 120;
status2.status = MAV_STATE_STANDBY;
system2.system_status = MAV_STATE_STANDBY;
// Pack message and get size of encoded byte string
messageSize = mavlink_msg_sys_status_encode(54, componentId, &msg, &status);
......@@ -696,7 +688,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
mavlink_set_mode_t mode;
mavlink_msg_set_mode_decode(&msg, &mode);
// Set mode indepent of mode.target
status.mode = mode.mode;
system.system_mode = mode.mode;
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: {
......@@ -717,9 +709,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
break;
// EXECUTE OPERATOR ACTIONS
case MAVLINK_MSG_ID_COMMAND: {
mavlink_command_t action;
mavlink_msg_command_decode(&msg, &action);
case MAVLINK_MSG_ID_COMMAND_SHORT: {
mavlink_command_short_t action;
mavlink_msg_command_short_decode(&msg, &action);
qDebug() << "SIM" << "received action" << action.command << "for system" << action.target_system;
......@@ -773,7 +765,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) {
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), 0, onboardParams.size(), j);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -801,7 +793,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -822,7 +814,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -834,7 +826,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......@@ -860,7 +852,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
readyBufferMutex.unlock();
// Update comm status
status.packet_drop = comm.packet_rx_drop_count;
status.errors_uart = comm.packet_rx_drop_count;
}
......
......@@ -128,6 +128,7 @@ protected:
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);
......
......@@ -38,9 +38,9 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
nextSPY(122.282883),
nextSPZ(550),
nextSPYaw(0.0),
sys_mode(MAV_MODE_READY),
sys_mode(MAV_MODE_PREFLIGHT),
sys_state(MAV_STATE_STANDBY),
nav_mode(MAV_NAV_GROUNDED),
nav_mode(MAV_FLIGHT_MODE_PREFLIGHT),
flying(false),
mavlink_version(version)
{
......@@ -62,13 +62,13 @@ void MAVLinkSimulationMAV::mainloop()
if (flying) {
sys_state = MAV_STATE_ACTIVE;
sys_mode = MAV_MODE_AUTO;
nav_mode = MAV_NAV_WAYPOINT;
nav_mode = MAV_FLIGHT_MODE_AUTO_MISSION;
}
// 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_CLASS_PIXHAWK);
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED, MAV_FLIGHT_MODE_AUTO_MISSION, MAV_STATE_ACTIVE, MAV_SAFETY_ARMED, 0xFF);
link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg);
......@@ -156,12 +156,12 @@ void MAVLinkSimulationMAV::mainloop()
// 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;
status.battery_remaining = 912;
// status.mode = sys_mode;
// status.nav_mode = nav_mode;
status.errors_uart = 0;
status.voltage_battery = 10500;
// status.status = sys_state;
status.battery_percent = 230;
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg);
timer10Hz = 5;
......@@ -336,7 +336,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
mavlink_local_position_setpoint_set_t sp;
mavlink_msg_local_position_setpoint_set_decode(&msg, &sp);
if (sp.target_system == this->systemid) {
nav_mode = MAV_NAV_WAYPOINT;
nav_mode = MAV_FLIGHT_MODE_AUTO_MISSION;
previousSPX = nextSPX;
previousSPY = nextSPY;
previousSPZ = nextSPZ;
......
......@@ -815,9 +815,10 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
break;
}
case MAVLINK_MSG_ID_COMMAND: { // special action from ground station
mavlink_command_t action;
mavlink_msg_command_decode(msg, &action);
case MAVLINK_MSG_ID_COMMAND_SHORT:
{ // special action from ground station
mavlink_command_short_t action;
mavlink_msg_command_short_decode(msg, &action);
if(action.target_system == systemid) {
if (verbose) qDebug("Waypoint: received message with action %d\n", action.command);
// switch (action.action) {
......
......@@ -82,16 +82,16 @@ void QGCFlightGearLink::processError(QProcess::ProcessError err)
MainWindow::instance()->showCriticalMessage(tr("FlightGear Crashed"), tr("This is a FlightGear-related problem. Please upgrade FlightGear"));
break;
case QProcess::Timedout:
MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct"));
MainWindow::instance()->showCriticalMessage(tr("FlightGear Start Timed Out"), tr("Please check if the path and command is correct"));
break;
case QProcess::WriteError:
MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct"));
MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
break;
case QProcess::ReadError:
MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct"));
MainWindow::instance()->showCriticalMessage(tr("Could not Communicate with FlightGear"), tr("Please check if the path and command is correct"));
break;
case QProcess::UnknownError:
MainWindow::instance()->showCriticalMessage(tr("FlightGear Failed to Start"), tr("Please check if the path and command is correct"));
MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct"));
break;
default:
MainWindow::instance()->showCriticalMessage(tr("FlightGear Error"), tr("Please check if the path and command is correct."));
......@@ -359,7 +359,7 @@ processFgfs = "fgfs";
fgRoot = "--fg-root=/usr/share/flightgear/data";
#endif
processCall << fgRoot;
//processCall << fgRoot;
//processCall << fgScenery;
processCall << "--generic=socket,out,50,127.0.0.1,49005,udp,ardupilot";
processCall << "--generic=socket,in,50,127.0.0.1,49000,udp,ardupilot";
......@@ -378,6 +378,14 @@ processCall << "--disable-random-objects";
processCall << "--disable-ai-models";
processCall << "--wind=0@0";
processCall << "--fdm=jsb";
processCall << "--prop:/engines/engine[0]/running=true";
if (mav->getType() == MAV_TYPE_QUADROTOR)
{
// Start the remaining three motors of the quad
processCall << "--prop:/engines/engine[1]/running=true";
processCall << "--prop:/engines/engine[2]/running=true";
processCall << "--prop:/engines/engine[3]/running=true";
}
processCall << QString("--lat=%1").arg(mav->getLatitude());
processCall << QString("--lon=%1").arg(mav->getLongitude());
// Add new argument with this: processCall << "";
......
......@@ -23,7 +23,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
switch (heartbeat->autopilot)
{
case MAV_CLASS_GENERIC:
case MAV_AUTOPILOT_GENERIC:
{
UAS* mav = new UAS(mavlink, sysid);
// Set the system type
......@@ -33,7 +33,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav;
}
break;
case MAV_CLASS_PIXHAWK:
case MAV_AUTOPILOT_PIXHAWK:
{
PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
// Set the system type
......@@ -46,7 +46,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav;
}
break;
case MAV_CLASS_SLUGS:
case MAV_AUTOPILOT_SLUGS:
{
SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
// Set the system type
......@@ -59,7 +59,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav;
}
break;
case MAV_CLASS_ARDUPILOTMEGA:
case MAV_AUTOPILOT_ARDUPILOTMEGA:
{
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
// Set the system type
......
This diff is collapsed.
......@@ -73,12 +73,18 @@ public:
const QString& getShortState() const;
/** @brief Get short mode */
const QString& getShortMode() const;
/** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id);
/** @brief Get the unique system id */
int getUASID() const;
/** @brief Get the airframe */
int getAirframe() const {
return airframe;
}
int getType() const {
return type;
}
/** @brief The time interval the robot is switched on */
quint64 getUptime() const;
/** @brief Get the status flag for the communication */
......@@ -261,6 +267,8 @@ public slots:
void executeCommand(MAV_CMD command);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component);
/** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */
......@@ -308,13 +316,10 @@ public slots:
void startLowBattAlarm();
void stopLowBattAlarm();
//void requestWaypoints(); FIXME tbd
//void clearWaypointList(); FIXME tbd
/** @brief Enable the motors */
void enable_motors();
/** @brief Arm system */
void armSystem();
/** @brief Disable the motors */
void disable_motors();
void disarmSystem();
/** @brief Set the values for the manual control of the vehicle */
void setManualControlCommands(double roll, double pitch, double yaw, double thrust);
......
......@@ -64,12 +64,15 @@ public:
virtual const QString& getShortState() const = 0;
/** @brief Get short mode */
virtual const QString& getShortMode() const = 0;
/** @brief Translate mode id into text */
static QString getShortModeTextFor(int id);
//virtual QColor getColor() = 0;
virtual int getUASID() const = 0; ///< Get the ID of the connected UAS
/** @brief The time interval the robot is switched on **/
virtual quint64 getUptime() const = 0;
/** @brief Get the status flag for the communication **/
virtual int getCommunicationStatus() const = 0;
virtual int getType() const = 0;
virtual double getLocalX() const = 0;
virtual double getLocalY() const = 0;
......
......@@ -1636,7 +1636,7 @@ void MainWindow::UASCreated(UASInterface* uas)
}
switch (uas->getAutopilotType()) {
case (MAV_CLASS_SLUGS): {
case (MAV_AUTOPILOT_SLUGS): {
// Build Slugs Widgets
buildSlugsWidgets();
......@@ -1674,9 +1674,9 @@ void MainWindow::UASCreated(UASInterface* uas)
}
break;
default:
case (MAV_CLASS_GENERIC):
case (MAV_CLASS_ARDUPILOTMEGA):
case (MAV_CLASS_PIXHAWK): {
case (MAV_AUTOPILOT_GENERIC):
case (MAV_AUTOPILOT_ARDUPILOTMEGA):
case (MAV_AUTOPILOT_PIXHAWK): {
// Build Pixhawk Widgets
buildPxWidgets();
......
......@@ -52,7 +52,7 @@ void UASControlParameters::changedMode(int mode)
QString modeTemp;
switch (mode) {
case (uint8_t)MAV_MODE_LOCKED:
case (uint8_t)MAV_MODE_PREFLIGHT:
modeTemp = "LOCKED MODE";
break;
case (uint8_t)MAV_MODE_MANUAL:
......@@ -80,23 +80,10 @@ void UASControlParameters::changedMode(int mode)
modeTemp = "GUIDED MODE";
break;
case (uint8_t)MAV_MODE_TEST1:
case (uint8_t)MAV_MODE_TEST:
modeTemp = "TEST1 MODE";
break;
case (uint8_t)MAV_MODE_TEST2:
modeTemp = "TEST2 MODE";
break;
#endif
case (uint8_t)MAV_MODE_READY:
modeTemp = "READY MODE";
break;
break;
case (uint8_t)MAV_MODE_TEST3:
modeTemp = "TEST3 MODE";
break;
case (uint8_t)MAV_MODE_RC_TRAINING:
modeTemp = "RC TRAINING MODE";
break;
default:
modeTemp = "UNINIT MODE";
break;
......
......@@ -37,41 +37,11 @@ This file is part of the PIXHAWK project
#include <QProcess>
#include <QPalette>
#include <MG.h>
#include "UASControlWidget.h"
#include <UASManager.h>
#include <UAS.h>
#include "QGC.h"
#define CONTROL_MODE_LOCKED "MODE LOCKED"
#define CONTROL_MODE_MANUAL "MODE MANUAL"
#ifdef MAVLINK_ENABLED_SLUGS
#define CONTROL_MODE_GUIDED "MODE MID-L CMDS"
#define CONTROL_MODE_AUTO "MODE WAYPOINT"
#define CONTROL_MODE_TEST1 "MODE PASST"
#define CONTROL_MODE_TEST2 "MODE SEL PT"
#else
#define CONTROL_MODE_GUIDED "MODE GUIDED"
#define CONTROL_MODE_AUTO "MODE AUTO"
#define CONTROL_MODE_TEST1 "MODE TEST1"
#define CONTROL_MODE_TEST2 "MODE TEST2"
#endif
#define CONTROL_MODE_TEST3 "MODE TEST3"
#define CONTROL_MODE_READY "MODE READY"
#define CONTROL_MODE_RC_TRAINING "RC SIMULATION"
#define CONTROL_MODE_LOCKED_INDEX 1
#define CONTROL_MODE_MANUAL_INDEX 2
#define CONTROL_MODE_GUIDED_INDEX 3
#define CONTROL_MODE_AUTO_INDEX 4
#define CONTROL_MODE_TEST1_INDEX 5
#define CONTROL_MODE_TEST2_INDEX 6
#define CONTROL_MODE_TEST3_INDEX 7
#define CONTROL_MODE_READY_INDEX 8
#define CONTROL_MODE_RC_TRAINING_INDEX 9
UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
uas(0),
engineOn(false)
......@@ -80,16 +50,12 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
ui.modeComboBox->clear();
ui.modeComboBox->insertItem(0, "Select..");
ui.modeComboBox->insertItem(CONTROL_MODE_LOCKED_INDEX, CONTROL_MODE_LOCKED);
ui.modeComboBox->insertItem(CONTROL_MODE_MANUAL_INDEX, CONTROL_MODE_MANUAL);
ui.modeComboBox->insertItem(CONTROL_MODE_GUIDED_INDEX, CONTROL_MODE_GUIDED);
ui.modeComboBox->insertItem(CONTROL_MODE_AUTO_INDEX, CONTROL_MODE_AUTO);
ui.modeComboBox->insertItem(CONTROL_MODE_TEST1_INDEX, CONTROL_MODE_TEST1);
ui.modeComboBox->insertItem(CONTROL_MODE_TEST2_INDEX, CONTROL_MODE_TEST2);
ui.modeComboBox->insertItem(CONTROL_MODE_TEST3_INDEX, CONTROL_MODE_TEST3);
ui.modeComboBox->insertItem(CONTROL_MODE_READY_INDEX, CONTROL_MODE_READY);
ui.modeComboBox->insertItem(CONTROL_MODE_RC_TRAINING_INDEX, CONTROL_MODE_RC_TRAINING);
ui.modeComboBox->insertItem(MAV_MODE_PREFLIGHT, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT));
ui.modeComboBox->insertItem(MAV_MODE_STABILIZE, UAS::getShortModeTextFor(MAV_MODE_STABILIZE));
ui.modeComboBox->insertItem(MAV_MODE_MANUAL, UAS::getShortModeTextFor(MAV_MODE_MANUAL));
ui.modeComboBox->insertItem(MAV_MODE_GUIDED, UAS::getShortModeTextFor(MAV_MODE_GUIDED));
ui.modeComboBox->insertItem(MAV_MODE_AUTO, UAS::getShortModeTextFor(MAV_MODE_AUTO));
ui.modeComboBox->insertItem(MAV_MODE_TEST, UAS::getShortModeTextFor(MAV_MODE_TEST));
connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int)));
connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode()));
......@@ -123,24 +89,6 @@ void UASControlWidget::setUAS(UASInterface* uas)
ui.controlStatusLabel->setText(tr("Connected to ") + uas->getUASName());
// // Check if additional controls should be loaded
// UAS* mav = dynamic_cast<UAS*>(uas);
// if (mav)
// {
// QPushButton* startRecButton = new QPushButton(tr("Record"));
// connect(startRecButton, SIGNAL(clicked()), mav, SLOT(startDataRecording()));
// ui.gridLayout->addWidget(startRecButton, 7, 1);
// QPushButton* pauseRecButton = new QPushButton(tr("Pause"));
// connect(pauseRecButton, SIGNAL(clicked()), mav, SLOT(pauseDataRecording()));
// ui.gridLayout->addWidget(pauseRecButton, 7, 3);
// QPushButton* stopRecButton = new QPushButton(tr("Stop"));
// connect(stopRecButton, SIGNAL(clicked()), mav, SLOT(stopDataRecording()));
// ui.gridLayout->addWidget(stopRecButton, 7, 4);
// }
this->uas = uas->getUASID();
setBackgroundColor(uas->getColor());
}
......@@ -154,9 +102,9 @@ void UASControlWidget::updateStatemachine()
{
if (engineOn) {
ui.controlButton->setText(tr("Stop Engine"));
ui.controlButton->setText(tr("DISARM SYSTEM"));
} else {
ui.controlButton->setText(tr("Activate Engine"));
ui.controlButton->setText(tr("ARM SYSTEM"));
}
}
......@@ -194,74 +142,51 @@ void UASControlWidget::updateState(int state)
switch (state) {
case (int)MAV_STATE_ACTIVE:
engineOn = true;
ui.controlButton->setText(tr("Stop Engine"));
ui.controlButton->setText(tr("DISARM SYSTEM"));
break;
case (int)MAV_STATE_STANDBY:
engineOn = false;
ui.controlButton->setText(tr("Activate Engine"));
ui.controlButton->setText(tr("ARM SYSTEM"));
break;
}
}
/**
* Called by the button
*/
void UASControlWidget::setMode(int mode)
{
// Adapt context button mode
if (mode == CONTROL_MODE_LOCKED_INDEX) {
uasMode = (unsigned int)MAV_MODE_LOCKED;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_MANUAL_INDEX) {
uasMode = (unsigned int)MAV_MODE_MANUAL;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_GUIDED_INDEX) {
uasMode = (unsigned int)MAV_MODE_GUIDED;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_AUTO_INDEX) {
uasMode = (unsigned int)MAV_MODE_AUTO;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_TEST1_INDEX) {
uasMode = (unsigned int)MAV_MODE_TEST1;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_TEST2_INDEX) {
uasMode = (unsigned int)MAV_MODE_TEST2;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_TEST3_INDEX) {
uasMode = (unsigned int)MAV_MODE_TEST3;
ui.modeComboBox->setCurrentIndex(mode);
} else if (mode == CONTROL_MODE_RC_TRAINING_INDEX) {
uasMode = (unsigned int)MAV_MODE_RC_TRAINING;
ui.modeComboBox->setCurrentIndex(mode);
} else {
qDebug() << "ERROR! MODE NOT FOUND";
uasMode = 0;
}
qDebug() << "SET MODE REQUESTED" << uasMode;
uasMode = mode;
ui.modeComboBox->blockSignals(true);
ui.modeComboBox->setCurrentIndex(mode);
ui.modeComboBox->blockSignals(false);
emit changedMode(mode);
}
void UASControlWidget::transmitMode()
{
if (uasMode != 0) {
UASInterface* mav = UASManager::instance()->getUASForId(this->uas);
if (mav) {
mav->setMode(uasMode);
ui.lastActionLabel->setText(QString("Set new mode for system %1").arg(mav->getUASName()));
}
UASInterface* mav = UASManager::instance()->getUASForId(this->uas);
if (mav)
{
mav->setMode(uasMode);
ui.lastActionLabel->setText(QString("Sent new mode cmd to %1").arg(mav->getUASName()));
}
}
void UASControlWidget::cycleContextButton()
{
UAS* mav = dynamic_cast<UAS*>(UASManager::instance()->getUASForId(this->uas));
if (mav) {
if (mav)
{
if (!engineOn) {
mav->enable_motors();
if (!engineOn)
{
mav->armSystem();
ui.lastActionLabel->setText(QString("Enabled motors on %1").arg(mav->getUASName()));
} else {
mav->disable_motors();
mav->disarmSystem();
ui.lastActionLabel->setText(QString("Disabled motors on %1").arg(mav->getUASName()));
}
// Update state now and in several intervals when MAV might have changed state
......@@ -270,8 +195,6 @@ void UASControlWidget::cycleContextButton()
QTimer::singleShot(50, this, SLOT(updateStatemachine()));
QTimer::singleShot(200, this, SLOT(updateStatemachine()));
//ui.controlButton->setText(tr("Force Landing"));
//ui.controlButton->setText(tr("KILL VEHICLE"));
}
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Saturday, August 13 2011, 07:20 UTC
* Generated on Saturday, August 20 2011, 11:19 UTC
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
......@@ -33,17 +33,19 @@ extern "C" {
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 161, 116, 56, 245, 0, 0, 0, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 212, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 99, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 254, 0, 0, 255, 185, 0, 14, 136, 53, 0, 212, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 255, 73, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }
#define MAVLINK_MESSAGE_KEYS { 179, 218, 22, 76, 226, 126, 117, 186, 0, 144, 0, 249, 172, 16, 0, 0, 0, 0, 0, 0, 33, 34, 191, 55, 0, 166, 28, 99, 28, 21, 243, 240, 91, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 20, 247, 234, 161, 116, 56, 245, 0, 0, 0, 62, 75, 185, 18, 42, 80, 0, 127, 200, 0, 0, 212, 251, 20, 38, 22, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 18, 103, 59, 0, 0, 0, 0, 0, 0, 0, 74, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 226, 65, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 254, 0, 0, 255, 185, 0, 14, 136, 53, 0, 212, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 255, 73, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 138, 43, 141, 211, 144 }