Commit 28e39f52 authored by lm's avatar lm

Fixed include guard fails for SLUGS message set

parent 16ee3c6a
......@@ -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;
......
......@@ -297,6 +297,7 @@ bool SerialLink::connect()
this->start(LowPriority);
}
}
return true;
}
/**
......
......@@ -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 */
......
......@@ -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<SlugsMAV*>(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)
......
......@@ -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
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