Browse Source

Fixed compile errors introduced by missing ifdefs

QGC4.4
pixhawk 15 years ago
parent
commit
8f20d172b9
  1. 2
      qgroundcontrol.pri
  2. 20
      src/ui/SlugsPIDControl.cpp
  3. 2
      src/ui/SlugsPIDControl.h
  4. 3
      src/ui/slugshilsim.cc

2
qgroundcontrol.pri

@ -140,7 +140,7 @@ macx { @@ -140,7 +140,7 @@ macx {
# osg/osgEarth dynamic casts might fail without this compiler option.
# see http://osgearth.org/wiki/FAQ for details.
#QMAKE_CXXFLAGS += -Wl,-E
QMAKE_CXXFLAGS += -Wl,-E
}
# GNU/Linux

20
src/ui/SlugsPIDControl.cpp

@ -46,9 +46,9 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) : @@ -46,9 +46,9 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
*/
void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
#ifdef MAVLINK_ENABLED_SLUGS
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(uas);
#ifdef MAVLINK_ENABLED_SLUGS
if (slugsMav != NULL)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t)));
@ -186,6 +186,7 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox() @@ -186,6 +186,7 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
{
//create the packet
#ifdef MAVLINK_ENABLED_SLUGS
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 0;
pidMessage.pVal = ui->dT_P_set->text().toFloat();
@ -196,6 +197,7 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox() @@ -196,6 +197,7 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->AirSpeedHold_groupBox->setStyleSheet(GREENcolorStyle);
}
@ -231,6 +233,7 @@ void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox() @@ -231,6 +233,7 @@ void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 2;
@ -242,6 +245,7 @@ void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox() @@ -242,6 +245,7 @@ void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
@ -279,6 +283,7 @@ void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox() @@ -279,6 +283,7 @@ void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 4;
@ -290,6 +295,7 @@ void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox() @@ -290,6 +295,7 @@ void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle);
}
@ -339,6 +345,7 @@ void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox() @@ -339,6 +345,7 @@ void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 1;
@ -350,6 +357,7 @@ void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox() @@ -350,6 +357,7 @@ void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle);
}
@ -398,6 +406,7 @@ void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox() @@ -398,6 +406,7 @@ void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 3;
@ -409,6 +418,7 @@ void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox() @@ -409,6 +418,7 @@ void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle);
}
@ -459,6 +469,7 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox() @@ -459,6 +469,7 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
@ -470,6 +481,7 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox() @@ -470,6 +481,7 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle);
}
}
@ -539,10 +551,12 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal @@ -539,10 +551,12 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal
}
}
#endif // MAVLINK_ENABLED_SLUG
void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
{
#ifdef MAVLINK_ENABLED_SLUGS
//ToDo remplace actionId values
@ -624,6 +638,7 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype) @@ -624,6 +638,7 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
#endif // MAVLINK_ENABLED_SLUG
}
void SlugsPIDControl::slugsGetGeneral()
@ -693,6 +708,8 @@ void SlugsPIDControl::slugsSetGeneral() @@ -693,6 +708,8 @@ void SlugsPIDControl::slugsSetGeneral()
counterRefreshSet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsTimerStartSet()
{
counterRefreshSet = 1;
@ -712,4 +729,3 @@ void SlugsPIDControl::slugsTimerStop() @@ -712,4 +729,3 @@ void SlugsPIDControl::slugsTimerStop()
// counterRefresh = 1;
}
#endif // MAVLINK_ENABLED_SLUGS

2
src/ui/SlugsPIDControl.h

@ -277,8 +277,10 @@ private: @@ -277,8 +277,10 @@ private:
QString ORIGINcolorStyle;
//SlugsMav Message
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pid_t pidMessage;
mavlink_slugs_action_t actionSlugs;
#endif
QTimer* refreshTimerSet; ///< The main timer, controls the update view
QTimer* refreshTimerGet; ///< The main timer, controls the update view

3
src/ui/slugshilsim.cc

@ -143,6 +143,8 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ @@ -143,6 +143,8 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){
// GPS
mavlink_gps_raw_t tmpGpsRaw;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_date_time_t tmpGpsTime;
tmpGpsTime.year = datagram->at(i++);
@ -165,6 +167,7 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ @@ -165,6 +167,7 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){
mavlink_msg_gps_date_time_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &tmpGpsTime);
activeUas->sendMessage(hilLink, msg);
#endif
memset(&msg, 0, sizeof(mavlink_message_t));

Loading…
Cancel
Save