diff --git a/src/comm/MAVLinkSimulationWaypointPlanner.cc b/src/comm/MAVLinkSimulationWaypointPlanner.cc index 9ef3e8b437a04d3787b3221f451f6ab625f83edd..b35d7a3dc3d1a1cda45e1839e2a0e1c9dfef4ee5 100644 --- a/src/comm/MAVLinkSimulationWaypointPlanner.cc +++ b/src/comm/MAVLinkSimulationWaypointPlanner.cc @@ -35,6 +35,10 @@ This file is part of the PIXHAWK project #include "MAVLinkSimulationWaypointPlanner.h" #include "QGC.h" +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif + class PxMatrix3x3; diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index d6bc78ccfd40e48ca6ccdbf21672ce92c3b99ed8..7b97c51a52dc736ef16f24b8680345bd39ae35ca 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -297,6 +297,7 @@ bool SerialLink::connect() this->start(LowPriority); } } + return true; } /** diff --git a/src/uas/SlugsMAV.h b/src/uas/SlugsMAV.h index 50396a4175d4f235ad357e826d2bde09922c4036..7eca5054f2250bb0f707fda6c1ea7553673dde9c 100644 --- a/src/uas/SlugsMAV.h +++ b/src/uas/SlugsMAV.h @@ -36,7 +36,9 @@ class SlugsMAV : public UAS public: SlugsMAV(MAVLinkProtocol* mavlink, int id = 0); +#ifdef MAVLINK_ENABLED_SLUGS mavlink_pwm_commands_t* getPwmCommands(); +#endif public slots: /** @brief Receive a MAVLink message from this MAV */ diff --git a/src/ui/SlugsHilSim.cc b/src/ui/SlugsHilSim.cc index bec83ea050975990412794f767a6606fec761a9f..58849e56321fb3816d4a3143ed222d87b00b1413 100644 --- a/src/ui/SlugsHilSim.cc +++ b/src/ui/SlugsHilSim.cc @@ -51,12 +51,14 @@ SlugsHilSim::SlugsHilSim(QWidget *parent) : linksAvailable.clear(); + #ifdef MAVLINK_ENABLED_SLUGS memset(&tmpAirData, 0, sizeof(mavlink_air_data_t)); memset(&tmpAttitudeData, 0, sizeof(mavlink_attitude_t)); memset(&tmpGpsData, 0, sizeof(mavlink_gps_raw_t)); memset(&tmpGpsTime, 0, sizeof(mavlink_gps_date_time_t)); memset(&tmpLocalPositionData, 0, sizeof(mavlink_sensor_bias_t)); memset(&tmpRawImuData, 0, sizeof(mavlink_raw_imu_t)); + #endif foreach (LinkInterface* link, LinkManager::instance()->getLinks()) { @@ -263,6 +265,7 @@ void SlugsHilSim::linkSelected(int cbIndex){ void SlugsHilSim::sendMessageToSlugs() { + #ifdef MAVLINK_ENABLED_SLUGS mavlink_message_t msg; mavlink_msg_local_position_encode(MG::SYSTEM::ID, @@ -306,11 +309,13 @@ void SlugsHilSim::sendMessageToSlugs() &tmpGpsTime); activeUas->sendMessage(hilLink, msg); memset(&msg, 0, sizeof(mavlink_message_t)); +#endif } void SlugsHilSim::commandDatagramToSimulink() { + #ifdef MAVLINK_ENABLED_SLUGS //mavlink_pwm_commands_t* pwdC = (static_cast(activeUas))->getPwmCommands(); mavlink_pwm_commands_t* pwdC; @@ -335,6 +340,7 @@ void SlugsHilSim::commandDatagramToSimulink() setUInt16ToDatagram(data, &i, 11);//value default txSocket->writeDatagram(data, QHostAddress::Broadcast, ui->ed_txPort->text().toInt()); +#endif } void SlugsHilSim::setUInt16ToDatagram(QByteArray& datagram, unsigned char* pos, uint16_t value) diff --git a/src/ui/SlugsHilSim.h b/src/ui/SlugsHilSim.h index 16f42f223b953844d7210f2bec840fc84d2134e7..b89ee1a68d1568a706af7a632a2d01eacdab4dab 100644 --- a/src/ui/SlugsHilSim.h +++ b/src/ui/SlugsHilSim.h @@ -69,9 +69,13 @@ protected: mavlink_local_position_t tmpLocalPositionData; mavlink_attitude_t tmpAttitudeData; mavlink_raw_imu_t tmpRawImuData; +#ifdef MAVLINK_ENABLED_SLUGS mavlink_air_data_t tmpAirData; +#endif mavlink_gps_raw_t tmpGpsData; + #ifdef MAVLINK_ENABLED_SLUGS mavlink_gps_date_time_t tmpGpsTime; +#endif public slots: @@ -150,4 +154,4 @@ private: }; -#endif // SLUGSHILSIM_H +#endif // SLUGSHILSIM_H \ No newline at end of file