Commit ef361d41 authored by lm's avatar lm

Fixed Linux compile error

parent 773517f5
......@@ -203,13 +203,13 @@ linux-g++ {
}
debug {
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/debug/.
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/debug/.
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/debug
}
release {
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/release/.
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/release/.
QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/release
}
# osg/osgEarth dynamic casts might fail without this compiler option.
......
......@@ -695,7 +695,12 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
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);
#endif
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
}
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
......@@ -704,6 +709,11 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
mavlink_message_t msg;
mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg);
#else
Q_UNUSED(x);
Q_UNUSED(y);
Q_UNUSED(z);
Q_UNUSED(yaw);
#endif
}
......
......@@ -360,11 +360,14 @@ void MainWindow::reloadStylesheet()
void MainWindow::showStatusMessage(const QString& status, int timeout)
{
Q_UNUSED(status);
Q_UNUSED(timeout);
//statusBar->showMessage(status, timeout);
}
void MainWindow::showStatusMessage(const QString& status)
{
Q_UNUSED(status);
//statusBar->showMessage(status, 5);
}
......
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