Commit 5a9d5927 authored by lm's avatar lm

Merge branch 'master' of http://github.com/malife/qgroundcontrol

parents 7de71387 cb306047
...@@ -54,10 +54,11 @@ macx { ...@@ -54,10 +54,11 @@ macx {
message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later) message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
} }
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
DESTDIR = $$BASEDIR/bin/mac DESTDIR = $$BASEDIR/bin/mac
INCLUDEPATH += -framework SDL \ INCLUDEPATH += -framework SDL \
$$BASEDIR/../mavlink/contrib/slugs/include \
$$BASEDIR/../mavlink/include $$BASEDIR/../mavlink/include
LIBS += -framework IOKit \ LIBS += -framework IOKit \
...@@ -120,12 +121,15 @@ win32 { ...@@ -120,12 +121,15 @@ win32 {
# Special settings for debug # Special settings for debug
#CONFIG += CONSOLE #CONFIG += CONSOLE
LIBS += -L$$BASEDIR\lib\sdl\win32 \
-lmingw32 -lSDLmain -lSDL -mwindows INCLUDEPATH += $$BASEDIR\lib\sdl\include #\
INCLUDEPATH += $$BASEDIR/lib/sdl/include #\
#"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include" #"C:\Program Files\Microsoft SDKs\Windows\v7.0\Include"
LIBS += -L$$BASEDIR\lib\sdl\win32 \
-lmingw32 -lSDLmain -lSDL -mwindows
debug { debug {
DESTDIR = $$BASEDIR/bin DESTDIR = $$BASEDIR/bin
} }
......
...@@ -42,9 +42,13 @@ DEPENDPATH += . \ ...@@ -42,9 +42,13 @@ DEPENDPATH += . \
plugins plugins
INCLUDEPATH += . \ INCLUDEPATH += . \
lib/QMapControl \ lib/QMapControl \
../mavlink/include \ $$BASEDIR/../mavlink/contrib/slugs/include \
MAVLink/include \ $$BASEDIR/../mavlink/include
mavlink/include
# ../mavlink/include \
#MAVLink/include \
#mavlink/include
# Input # Input
FORMS += src/ui/MainWindow.ui \ FORMS += src/ui/MainWindow.ui \
......
...@@ -186,7 +186,9 @@ void MAVLinkSimulationLink::mainloop() ...@@ -186,7 +186,9 @@ void MAVLinkSimulationLink::mainloop()
static float drainRate = 0.025; // x.xx% of the capacity is linearly drained per second static float drainRate = 0.025; // x.xx% of the capacity is linearly drained per second
mavlink_attitude_t attitude; mavlink_attitude_t attitude;
mavlink_raw_aux_t rawAuxValues; #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_raw_aux_t rawAuxValues;
#endif
mavlink_raw_imu_t rawImuValues; mavlink_raw_imu_t rawImuValues;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
...@@ -305,7 +307,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -305,7 +307,7 @@ void MAVLinkSimulationLink::mainloop()
{ {
rawImuValues.zgyro = d; rawImuValues.zgyro = d;
} }
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
if (keys.value(i, "") == "Pressure") if (keys.value(i, "") == "Pressure")
{ {
rawAuxValues.baro = d; rawAuxValues.baro = d;
...@@ -315,7 +317,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -315,7 +317,7 @@ void MAVLinkSimulationLink::mainloop()
{ {
rawAuxValues.vbat = d; rawAuxValues.vbat = d;
} }
#endif
if (keys.value(i, "") == "roll_IMU") if (keys.value(i, "") == "roll_IMU")
{ {
attitude.roll = d; attitude.roll = d;
...@@ -459,7 +461,10 @@ void MAVLinkSimulationLink::mainloop() ...@@ -459,7 +461,10 @@ void MAVLinkSimulationLink::mainloop()
uint8_t visLock = 3; uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock); uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl); messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
#endif
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
memcpy(stream+streampointer, buffer, bufferlength); memcpy(stream+streampointer, buffer, bufferlength);
streampointer += bufferlength; streampointer += bufferlength;
...@@ -493,7 +498,9 @@ void MAVLinkSimulationLink::mainloop() ...@@ -493,7 +498,9 @@ void MAVLinkSimulationLink::mainloop()
//qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer; //qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer;
// AUX STATUS // AUX STATUS
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
rawAuxValues.vbat = voltage; rawAuxValues.vbat = voltage;
#endif
rate1hzCounter = 1; rate1hzCounter = 1;
} }
...@@ -632,14 +639,17 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -632,14 +639,17 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
} }
break; break;
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
case MAVLINK_MSG_ID_MANUAL_CONTROL: case MAVLINK_MSG_ID_MANUAL_CONTROL:
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_manual_control_t control; mavlink_manual_control_t control;
mavlink_msg_manual_control_decode(&msg, &control); mavlink_msg_manual_control_decode(&msg, &control);
qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch; qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
#endif
} }
break; break;
#endif
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{ {
qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION"; qDebug() << "GCS REQUESTED PARAM LIST FROM SIMULATION";
......
...@@ -33,6 +33,7 @@ This file is part of the PIXHAWK project ...@@ -33,6 +33,7 @@ This file is part of the PIXHAWK project
#include "MainWindow.h" #include "MainWindow.h"
#include "configuration.h" #include "configuration.h"
/* SDL does ugly things to main() */ /* SDL does ugly things to main() */
#ifdef main #ifdef main
# undef main # undef main
......
...@@ -21,7 +21,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -21,7 +21,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Let UAS handle the default message set // Let UAS handle the default message set
UAS::receiveMessage(link, message); UAS::receiveMessage(link, message);
// Handle your special messages // Handle your special messages mavlink_message_t* msg = &message;
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_HEARTBEAT: case MAVLINK_MSG_ID_HEARTBEAT:
...@@ -29,6 +29,100 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -29,6 +29,100 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug() << "SLUGS RECEIVED HEARTBEAT"; qDebug() << "SLUGS RECEIVED HEARTBEAT";
break; break;
} }
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES
case MAVLINK_MSG_ID_CPU_LOAD:
{
mavlink_cpu_load_t cpu_load;
quint64 time = getUnixTime(0);
mavlink_msg_cpu_load_decode(&message,&cpu_load);
emit valueChanged(uasId, "CPU Load", cpu_load.target, time);
emit valueChanged(uasId, "SensorDSC Load", cpu_load.sensLoad, time);
emit valueChanged(uasId, "ControlDSC Load", cpu_load.ctrlLoad, time);
emit valueChanged(uasId, "Battery Volt", cpu_load.batVolt, time);
break;
}
case MAVLINK_MSG_ID_AIR_DATA:
{
mavlink_air_data_t air_data;
quint64 time = getUnixTime(0);
mavlink_msg_air_data_decode(&message,&air_data);
emit valueChanged(uasId, "Air Data",air_data.target,time);
emit valueChanged(uasId, "Presion Dinamica", air_data.dynamicPressure,time);
emit valueChanged(uasId, "Presion Estatica",air_data.staticPressure, time);
emit valueChanged(uasId, "Temperatura",air_data.temperature,time);
break;
}
case MAVLINK_MSG_ID_SENSOR_BIAS:
{
mavlink_sensor_bias_t sensor_bias;
quint64 time = getUnixTime(0);
mavlink_msg_sensor_bias_decode(&message,&sensor_bias);
emit valueChanged(uasId,"Sensor Bias",sensor_bias.target, time);
emit valueChanged(uasId,"Acelerometro X",sensor_bias.axBias, time);
emit valueChanged(uasId,"Acelerometro y",sensor_bias.ayBias,time);
emit valueChanged(uasId,"Acelerometro Z",sensor_bias.azBias,time);
emit valueChanged(uasId,"Gyro X",sensor_bias.gxBias,time);
emit valueChanged(uasId,"Gyro Y",sensor_bias.gyBias,time);
emit valueChanged(uasId,"Gyro Z",sensor_bias.gzBias,time);
break;
}
case MAVLINK_MSG_ID_DIAGNOSTIC:
{
mavlink_diagnostic_t diagnostic;
quint64 time = getUnixTime(0);
mavlink_msg_diagnostic_decode(&message,&diagnostic);
emit valueChanged(uasId,"Diagnostico",diagnostic.target,time);
emit valueChanged(uasId,"Diagnostico F1",diagnostic.diagFl1,time);
emit valueChanged(uasId,"Diagnostico F2",diagnostic.diagFl2,time);
emit valueChanged(uasId,"Diagnostico F3",diagnostic.diagFl3,time);
emit valueChanged(uasId,"Diagnostico S1",diagnostic.diagSh1,time);
emit valueChanged(uasId,"Diagnostico S2",diagnostic.diagSh2,time);
emit valueChanged(uasId,"Diagnostico S3",diagnostic.diagSh3,time);
break;
}
case MAVLINK_MSG_ID_PILOT_CONSOLE:
{
mavlink_pilot_console_t pilot;
quint64 time = getUnixTime(0);
mavlink_msg_pilot_console_decode(&message,&pilot);
emit valueChanged(uasId,"Mensajes PWM",pilot.target,time);
emit valueChanged(uasId,"Aceleracion Consola",pilot.dt,time);
emit valueChanged(uasId,"Aleron Izq Consola",pilot.dla,time);
emit valueChanged(uasId,"Aleron Der Consola",pilot.dra,time);
emit valueChanged(uasId,"Timon Consola",pilot.dr,time);
emit valueChanged(uasId,"Elevador Consola",pilot.de,time);
break;
}
case MAVLINK_MSG_ID_PWM_COMMANDS:
{
mavlink_pwm_commands_t pwm;
quint64 time = getUnixTime(0);
mavlink_msg_pwm_commands_decode(&message,&pwm);
emit valueChanged(uasId,"Superficies de Control",pwm.target,time);
emit valueChanged(uasId,"Comando Aceleracion PA",pwm.dt_c,time);
emit valueChanged(uasId,"Comando Aleron Izq PA",pwm.dla_c,time);
emit valueChanged(uasId,"Comando Aleron Der PA",pwm.dra_c,time);
emit valueChanged(uasId,"Comando Timon PA",pwm.dr_c,time);
emit valueChanged(uasId,"Comando elevador Izq PA",pwm.dle_c,time);
emit valueChanged(uasId,"Comando Elevador Der PA",pwm.dre_c,time);
emit valueChanged(uasId,"Comando Flap Izq PA",pwm.dlf_c,time);
emit valueChanged(uasId,"Comando Flap Der PA",pwm.drf_c,time);
emit valueChanged(uasId,"Comando Aux1 PA",pwm.aux1,time);
emit valueChanged(uasId,"Comando Aux2 PA",pwm.aux2,time);
break;
}
#endif
default: default:
qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid; qDebug() << "\nSLUGS RECEIVED MESSAGE WITH ID" << message.msgid;
break; break;
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
class SlugsMAV : public UAS class SlugsMAV : public UAS
{ {
Q_OBJECT Q_OBJECT
Q_INTERFACES(UASInterface)
public: public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0); SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
......
...@@ -298,12 +298,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -298,12 +298,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "x", pos.x, time); emit valueChanged(uasId, "x", pos.x, time);
emit valueChanged(uasId, "y", pos.y, time); emit valueChanged(uasId, "y", pos.y, time);
emit valueChanged(uasId, "z", pos.z, time); emit valueChanged(uasId, "z", pos.z, time);
emit valueChanged(uasId, "roll", pos.roll, time); emit valueChanged(uasId, "Vx", pos.vx, time);
emit valueChanged(uasId, "pitch", pos.pitch, time); emit valueChanged(uasId, "Vy", pos.vy, time);
emit valueChanged(uasId, "yaw", pos.yaw, time); emit valueChanged(uasId, "Vz", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
//emit speedChanged(this, pos.roll, pos.pitch, pos.yaw, time); emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time); //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state // Set internal state
if (!positionLock) if (!positionLock)
{ {
...@@ -502,9 +502,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -502,9 +502,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw); mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
sendMessage(msg); sendMessage(msg);
#endif
} }
quint64 UAS::getUnixTime(quint64 time) quint64 UAS::getUnixTime(quint64 time)
...@@ -667,6 +669,7 @@ void UAS::writeParametersToStorage() ...@@ -667,6 +669,7 @@ void UAS::writeParametersToStorage()
mavlink_message_t msg; mavlink_message_t msg;
// TODO Replace MG System ID with static function call and allow to change ID in GUI // TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE); mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),MAV_COMP_ID_IMU, (uint8_t)MAV_ACTION_STORAGE_WRITE);
//mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(),(uint8_t)MAV_ACTION_STORAGE_WRITE);
sendMessage(msg); sendMessage(msg);
} }
...@@ -680,6 +683,7 @@ void UAS::readParametersFromStorage() ...@@ -680,6 +683,7 @@ void UAS::readParametersFromStorage()
void UAS::enableAllDataTransmission(bool enabled) void UAS::enableAllDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -700,10 +704,12 @@ void UAS::enableAllDataTransmission(bool enabled) ...@@ -700,10 +704,12 @@ void UAS::enableAllDataTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableRawSensorDataTransmission(bool enabled) void UAS::enableRawSensorDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -722,10 +728,12 @@ void UAS::enableRawSensorDataTransmission(bool enabled) ...@@ -722,10 +728,12 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableExtendedSystemStatusTransmission(bool enabled) void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -744,10 +752,12 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled) ...@@ -744,10 +752,12 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableRCChannelDataTransmission(bool enabled) void UAS::enableRCChannelDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -766,10 +776,12 @@ void UAS::enableRCChannelDataTransmission(bool enabled) ...@@ -766,10 +776,12 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableRawControllerDataTransmission(bool enabled) void UAS::enableRawControllerDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -788,10 +800,12 @@ void UAS::enableRawControllerDataTransmission(bool enabled) ...@@ -788,10 +800,12 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableRawSensorFusionTransmission(bool enabled) void UAS::enableRawSensorFusionTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -810,10 +824,12 @@ void UAS::enableRawSensorFusionTransmission(bool enabled) ...@@ -810,10 +824,12 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enablePositionTransmission(bool enabled) void UAS::enablePositionTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -832,10 +848,12 @@ void UAS::enablePositionTransmission(bool enabled) ...@@ -832,10 +848,12 @@ void UAS::enablePositionTransmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableExtra1Transmission(bool enabled) void UAS::enableExtra1Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -854,10 +872,12 @@ void UAS::enableExtra1Transmission(bool enabled) ...@@ -854,10 +872,12 @@ void UAS::enableExtra1Transmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableExtra2Transmission(bool enabled) void UAS::enableExtra2Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -876,10 +896,12 @@ void UAS::enableExtra2Transmission(bool enabled) ...@@ -876,10 +896,12 @@ void UAS::enableExtra2Transmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::enableExtra3Transmission(bool enabled) void UAS::enableExtra3Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
mavlink_request_data_stream_t stream; mavlink_request_data_stream_t stream;
...@@ -898,6 +920,7 @@ void UAS::enableExtra3Transmission(bool enabled) ...@@ -898,6 +920,7 @@ void UAS::enableExtra3Transmission(bool enabled)
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg); sendMessage(msg);
#endif
} }
void UAS::setParameter(int component, QString id, float value) void UAS::setParameter(int component, QString id, float value)
...@@ -988,12 +1011,14 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double ...@@ -988,12 +1011,14 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
if(mode == (int)MAV_MODE_MANUAL) if(mode == (int)MAV_MODE_MANUAL)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual); mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message); sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust; qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow()); emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
#endif
} }
} }
......
Markdown is supported
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