Commit 4fe9707c authored by lm's avatar lm

Fixed some minor wrong define names

parent 29241533
...@@ -182,7 +182,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -182,7 +182,7 @@ void MAVLinkSimulationLink::mainloop()
mavlink_attitude_t attitude; mavlink_attitude_t attitude;
memset(&attitude, 0, sizeof(mavlink_attitude_t)); memset(&attitude, 0, sizeof(mavlink_attitude_t));
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_raw_aux_t rawAuxValues; mavlink_raw_aux_t rawAuxValues;
memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t)); memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif #endif
...@@ -305,7 +305,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -305,7 +305,7 @@ void MAVLinkSimulationLink::mainloop()
{ {
rawImuValues.zgyro = d; rawImuValues.zgyro = d;
} }
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
if (keys.value(i, "") == "Pressure") if (keys.value(i, "") == "Pressure")
{ {
rawAuxValues.baro = d; rawAuxValues.baro = d;
...@@ -468,7 +468,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -468,7 +468,7 @@ void MAVLinkSimulationLink::mainloop()
static int detectionCounter = 6; static int detectionCounter = 6;
if (detectionCounter % 10 == 0) if (detectionCounter % 10 == 0)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_pattern_detected_t detected; mavlink_pattern_detected_t detected;
detected.confidence = 5.0f; detected.confidence = 5.0f;
...@@ -582,7 +582,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -582,7 +582,7 @@ 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 #ifdef MAVLINK_ENABLED_PIXHAWK
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 #endif
...@@ -619,7 +619,7 @@ void MAVLinkSimulationLink::mainloop() ...@@ -619,7 +619,7 @@ 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 #ifdef MAVLINK_ENABLED_PIXHAWK
rawAuxValues.vbat = voltage; rawAuxValues.vbat = voltage;
#endif #endif
...@@ -760,14 +760,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -760,14 +760,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
} }
break; break;
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
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 #endif
......
...@@ -33,17 +33,17 @@ This file is part of the QGROUNDCONTROL project ...@@ -33,17 +33,17 @@ This file is part of the QGROUNDCONTROL project
#include <mavlink_types.h> #include <mavlink_types.h>
#include <mavlink.h> #include <mavlink.h>
#ifdef QGC_USE_PIXHAWK_MESSAGES //#ifdef QGC_USE_PIXHAWK_MESSAGES
#include <pixhawk.h> #include <pixhawk.h>
#endif //#endif
#ifdef QGC_USE_SLUGS_MESSAGES //#ifdef QGC_USE_SLUGS_MESSAGES
#include <slugs.h> #include <slugs.h>
#endif //#endif
#ifdef QGC_USE_UALBERTA_MESSAGES //#ifdef QGC_USE_UALBERTA_MESSAGES
#include <ualberta.h> #include <ualberta.h>
#endif //#endif
#ifdef QGC_USE_ARDUPILOT_MESSAGES #ifdef QGC_USE_ARDUPILOT_MESSAGES
#include <ardupilot.h> #include <ardupilot.h>
......
...@@ -46,7 +46,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -46,7 +46,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid; //qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled // Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
if (message.sysid == uasId) if (message.sysid == uasId)
{ {
...@@ -169,7 +169,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -169,7 +169,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command) void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_watchdog_command_t payload; mavlink_watchdog_command_t payload;
payload.target_system_id = uasId; payload.target_system_id = uasId;
payload.watchdog_id = watchdogId; payload.watchdog_id = watchdogId;
......
...@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
} }
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC #ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_CPU_LOAD: case MAVLINK_MSG_ID_CPU_LOAD:
{ {
......
...@@ -556,7 +556,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -556,7 +556,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, severity, text); emit textMessageReceived(uasId, message.compid, severity, text);
} }
break; break;
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES #ifdef MAVLINK_ENABLED_UALBERTA
case MAVLINK_MSG_ID_NAV_FILTER_BIAS: case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{ {
mavlink_nav_filter_bias_t bias; mavlink_nav_filter_bias_t bias;
...@@ -588,7 +588,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -588,7 +588,7 @@ 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 #ifdef MAVLINK_ENABLED_PIXHAWK
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);
...@@ -597,7 +597,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) ...@@ -597,7 +597,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw) void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw); mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg); sendMessage(msg);
...@@ -827,7 +827,7 @@ void UAS::readParametersFromStorage() ...@@ -827,7 +827,7 @@ void UAS::readParametersFromStorage()
void UAS::enableAllDataTransmission(bool enabled) void UAS::enableAllDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -853,7 +853,7 @@ void UAS::enableAllDataTransmission(bool enabled) ...@@ -853,7 +853,7 @@ void UAS::enableAllDataTransmission(bool enabled)
void UAS::enableRawSensorDataTransmission(bool enabled) void UAS::enableRawSensorDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -877,7 +877,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled) ...@@ -877,7 +877,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
void UAS::enableExtendedSystemStatusTransmission(bool enabled) void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -901,7 +901,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled) ...@@ -901,7 +901,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
void UAS::enableRCChannelDataTransmission(bool enabled) void UAS::enableRCChannelDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -925,7 +925,7 @@ void UAS::enableRCChannelDataTransmission(bool enabled) ...@@ -925,7 +925,7 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
void UAS::enableRawControllerDataTransmission(bool enabled) void UAS::enableRawControllerDataTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -949,7 +949,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled) ...@@ -949,7 +949,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
void UAS::enableRawSensorFusionTransmission(bool enabled) void UAS::enableRawSensorFusionTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -973,7 +973,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled) ...@@ -973,7 +973,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
void UAS::enablePositionTransmission(bool enabled) void UAS::enablePositionTransmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -997,7 +997,7 @@ void UAS::enablePositionTransmission(bool enabled) ...@@ -997,7 +997,7 @@ void UAS::enablePositionTransmission(bool enabled)
void UAS::enableExtra1Transmission(bool enabled) void UAS::enableExtra1Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -1021,7 +1021,7 @@ void UAS::enableExtra1Transmission(bool enabled) ...@@ -1021,7 +1021,7 @@ void UAS::enableExtra1Transmission(bool enabled)
void UAS::enableExtra2Transmission(bool enabled) void UAS::enableExtra2Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -1045,7 +1045,7 @@ void UAS::enableExtra2Transmission(bool enabled) ...@@ -1045,7 +1045,7 @@ void UAS::enableExtra2Transmission(bool enabled)
void UAS::enableExtra3Transmission(bool enabled) void UAS::enableExtra3Transmission(bool enabled)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK
// 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;
...@@ -1161,7 +1161,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double ...@@ -1161,7 +1161,7 @@ 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 #ifdef MAVLINK_ENABLED_PIXHAWK
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);
......
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