diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index bf9f409f53e89397d99c01076b809c03f1d13c31..065535f651dc1a44a83b429f4480ed20dd2e7996 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -182,7 +182,7 @@ void MAVLinkSimulationLink::mainloop() mavlink_attitude_t attitude; memset(&attitude, 0, sizeof(mavlink_attitude_t)); - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK mavlink_raw_aux_t rawAuxValues; memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t)); #endif @@ -305,7 +305,7 @@ void MAVLinkSimulationLink::mainloop() { rawImuValues.zgyro = d; } -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK if (keys.value(i, "") == "Pressure") { rawAuxValues.baro = d; @@ -468,7 +468,7 @@ void MAVLinkSimulationLink::mainloop() static int detectionCounter = 6; if (detectionCounter % 10 == 0) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK mavlink_pattern_detected_t detected; detected.confidence = 5.0f; @@ -582,7 +582,7 @@ void MAVLinkSimulationLink::mainloop() uint8_t visLock = 3; 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); #endif @@ -619,7 +619,7 @@ void MAVLinkSimulationLink::mainloop() //qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer; // AUX STATUS - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK rawAuxValues.vbat = voltage; #endif @@ -760,14 +760,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) } } break; -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK case MAVLINK_MSG_ID_MANUAL_CONTROL: { - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES mavlink_manual_control_t control; mavlink_msg_manual_control_decode(&msg, &control); qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch; - #endif } break; #endif diff --git a/src/comm/QGCMAVLink.h b/src/comm/QGCMAVLink.h index 4e0a5baa3772543fc51108791bb7a60aeaea4a2a..c73d3a63036ebcebd69428f1b69a7256a3d5b0d8 100644 --- a/src/comm/QGCMAVLink.h +++ b/src/comm/QGCMAVLink.h @@ -33,17 +33,17 @@ This file is part of the QGROUNDCONTROL project #include #include -#ifdef QGC_USE_PIXHAWK_MESSAGES +//#ifdef QGC_USE_PIXHAWK_MESSAGES #include -#endif +//#endif -#ifdef QGC_USE_SLUGS_MESSAGES +//#ifdef QGC_USE_SLUGS_MESSAGES #include -#endif +//#endif -#ifdef QGC_USE_UALBERTA_MESSAGES +//#ifdef QGC_USE_UALBERTA_MESSAGES #include -#endif +//#endif #ifdef QGC_USE_ARDUPILOT_MESSAGES #include diff --git a/src/uas/PxQuadMAV.cc b/src/uas/PxQuadMAV.cc index 5e673514485e4fa9cf9abc8c24164a9b78344197..ccf5f42c3328f4fcf9d2eb6c6dfff736ef717969 100644 --- a/src/uas/PxQuadMAV.cc +++ b/src/uas/PxQuadMAV.cc @@ -46,7 +46,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) //qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid; // Only compile this portion if matching MAVLink packets have been compiled -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK if (message.sysid == uasId) { @@ -169,7 +169,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK mavlink_watchdog_command_t payload; payload.target_system_id = uasId; payload.watchdog_id = watchdogId; diff --git a/src/uas/SlugsMAV.cc b/src/uas/SlugsMAV.cc index bfadedadd9169cda86c49895b03fdf67b66cc69f..5fbf1c931041a58a3e25447ed2e40e872909515a 100644 --- a/src/uas/SlugsMAV.cc +++ b/src/uas/SlugsMAV.cc @@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) break; } -#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC +#ifdef MAVLINK_ENABLED_SLUGS case MAVLINK_MSG_ID_CPU_LOAD: { diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 656a31e50e1bcfa718005140ec52824b3d04cf19..570f39c967ca2673d396128cd7fc4a6b808ebb6f 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -556,7 +556,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit textMessageReceived(uasId, message.compid, severity, text); } break; -#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES +#ifdef MAVLINK_ENABLED_UALBERTA case MAVLINK_MSG_ID_NAV_FILTER_BIAS: { mavlink_nav_filter_bias_t bias; @@ -623,7 +623,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) 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_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw); sendMessage(msg); @@ -632,7 +632,7 @@ void UAS::setLocalPositionSetpoint(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_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw); sendMessage(msg); @@ -862,7 +862,7 @@ void UAS::readParametersFromStorage() void UAS::enableAllDataTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -888,7 +888,7 @@ void UAS::enableAllDataTransmission(bool enabled) void UAS::enableRawSensorDataTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -912,7 +912,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled) void UAS::enableExtendedSystemStatusTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -936,7 +936,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled) void UAS::enableRCChannelDataTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -964,7 +964,7 @@ void UAS::enableRCChannelDataTransmission(bool enabled) void UAS::enableRawControllerDataTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -988,7 +988,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled) void UAS::enableRawSensorFusionTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -1012,7 +1012,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled) void UAS::enablePositionTransmission(bool enabled) { -#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES +#ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -1036,7 +1036,7 @@ void UAS::enablePositionTransmission(bool enabled) void UAS::enableExtra1Transmission(bool enabled) { - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -1060,7 +1060,7 @@ void UAS::enableExtra1Transmission(bool enabled) void UAS::enableExtra2Transmission(bool enabled) { - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -1084,7 +1084,7 @@ void UAS::enableExtra2Transmission(bool enabled) void UAS::enableExtra3Transmission(bool enabled) { - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK // Buffers to write data to mavlink_message_t msg; mavlink_request_data_stream_t stream; @@ -1200,7 +1200,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double // if(mode == (int)MAV_MODE_MANUAL) // { - #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES + #ifdef MAVLINK_ENABLED_PIXHAWK 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); sendMessage(message); diff --git a/src/ui/QGCRemoteControlView.cc b/src/ui/QGCRemoteControlView.cc index 922221d29e6626305eefbbcd10626c3349633502..d0c574609e567ad8e5c382057f385be9139c048e 100644 --- a/src/ui/QGCRemoteControlView.cc +++ b/src/ui/QGCRemoteControlView.cc @@ -187,7 +187,7 @@ void QGCRemoteControlView::changeEvent(QEvent *e) QWidget::changeEvent(e); switch (e->type()) { case QEvent::LanguageChange: - ui->retranslateUi(this); + //ui->retranslateUi(this); break; default: break;