Commit b232d1e1 authored by lm's avatar lm

Cleanup, moved output files, added set home button

parent 007db801
...@@ -65,7 +65,7 @@ macx { ...@@ -65,7 +65,7 @@ macx {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
DESTDIR = $$BASEDIR/bin/mac #DESTDIR = $$BASEDIR/bin/mac
INCLUDEPATH += -framework SDL INCLUDEPATH += -framework SDL
LIBS += -framework IOKit \ LIBS += -framework IOKit \
...@@ -146,12 +146,12 @@ macx { ...@@ -146,12 +146,12 @@ macx {
linux-g++ { linux-g++ {
debug { debug {
DESTDIR = $$BUILDDIR/debug #DESTDIR = $$BUILDDIR/debug
CONFIG += debug CONFIG += debug
} }
release { release {
DESTDIR = $$BUILDDIR/release #DESTDIR = $$BUILDDIR/release
} }
QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/. QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
...@@ -214,12 +214,12 @@ linux-g++ { ...@@ -214,12 +214,12 @@ linux-g++ {
linux-g++-64 { linux-g++-64 {
debug { debug {
DESTDIR = $$BUILDDIR/debug #DESTDIR = $$BUILDDIR/debug
CONFIG += debug CONFIG += debug
} }
release { release {
DESTDIR = $$BUILDDIR/release #DESTDIR = $$BUILDDIR/release
} }
QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/. QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
...@@ -364,11 +364,11 @@ win32-g++ { ...@@ -364,11 +364,11 @@ win32-g++ {
debug { debug {
DESTDIR = $$BUILDDIR/debug #DESTDIR = $$BUILDDIR/debug
} }
release { release {
DESTDIR = $$BUILDDIR/release #DESTDIR = $$BUILDDIR/release
} }
RC_FILE = $$BASEDIR/qgroundcontrol.rc RC_FILE = $$BASEDIR/qgroundcontrol.rc
......
...@@ -421,6 +421,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -421,6 +421,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
break; break;
case MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET:
{
mavlink_gps_local_origin_set_t pos;
mavlink_msg_gps_local_origin_set_decode(&message, &pos);
// FIXME Emit to other components
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{ {
mavlink_rc_channels_raw_t channels; mavlink_rc_channels_raw_t channels;
...@@ -657,6 +664,36 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -657,6 +664,36 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
void UAS::setLocalOriginAtCurrentGPSPosition()
{
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Setting new World Coordinate Frame Origin");
msgBox.setInformativeText("Do you want to set a new origin? Waypoints defined in the local frame will be shifted in their physical location");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
if (ret == QMessageBox::Yes)
{
mavlink_message_t msg;
mavlink_msg_action_pack(mavlink->getSystemId(), mavlink->getSystemId(), &msg, this->getUASID(), 0, MAV_ACTION_SET_ORIGIN);
// Send message twice to increase chance that it reaches its goal
sendMessage(msg);
// Wait 5 ms
MG::SLEEP::usleep(5000);
// Send again
sendMessage(msg);
result = true;
}
}
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
......
...@@ -243,6 +243,8 @@ public slots: ...@@ -243,6 +243,8 @@ public slots:
/** @brief Update the system state */ /** @brief Update the system state */
void updateState(); void updateState();
/** @brief Set world frame origin at current GPS position */
void setLocalOriginAtCurrentGPSPosition();
/** @brief Set local position setpoint */ /** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw); void setLocalPositionSetpoint(float x, float y, float z, float yaw);
/** @brief Add an offset in body frame to the setpoint */ /** @brief Add an offset in body frame to the setpoint */
......
...@@ -194,6 +194,8 @@ public slots: ...@@ -194,6 +194,8 @@ public slots:
//virtual void requestWaypoints() = 0; //virtual void requestWaypoints() = 0;
/** @brief Clear all existing waypoints on the robot */ /** @brief Clear all existing waypoints on the robot */
//virtual void clearWaypointList() = 0; //virtual void clearWaypointList() = 0;
/** @brief Set world frame origin at current GPS position */
virtual void setLocalOriginAtCurrentGPSPosition() = 0;
/** @brief Request all onboard parameters of all components */ /** @brief Request all onboard parameters of all components */
virtual void requestParameters() = 0; virtual void requestParameters() = 0;
/** @brief Write parameter to permanent storage */ /** @brief Write parameter to permanent storage */
......
...@@ -219,7 +219,7 @@ ...@@ -219,7 +219,7 @@
</size> </size>
</property> </property>
<property name="text"> <property name="text">
<string>Set Home</string> <string>Set Origin</string>
</property> </property>
<property name="icon"> <property name="icon">
<iconset resource="../../mavground.qrc"> <iconset resource="../../mavground.qrc">
......
...@@ -95,6 +95,7 @@ void UASControlWidget::setUAS(UASInterface* uas) ...@@ -95,6 +95,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch())); disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch()));
disconnect(ui.landButton, SIGNAL(clicked()), oldUAS, SLOT(home())); disconnect(ui.landButton, SIGNAL(clicked()), oldUAS, SLOT(home()));
disconnect(ui.shutdownButton, SIGNAL(clicked()), oldUAS, SLOT(shutdown())); disconnect(ui.shutdownButton, SIGNAL(clicked()), oldUAS, SLOT(shutdown()));
connect(ui.setHomeButton, SIGNAL(clicked()), uas, SLOT(setLocalOriginAtCurrentGPSPosition()));
disconnect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); disconnect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
disconnect(uas, SIGNAL(statusChanged(int)), this, SLOT(updateState(int))); disconnect(uas, SIGNAL(statusChanged(int)), this, SLOT(updateState(int)));
} }
...@@ -104,6 +105,7 @@ void UASControlWidget::setUAS(UASInterface* uas) ...@@ -104,6 +105,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
connect(ui.liftoffButton, SIGNAL(clicked()), uas, SLOT(launch())); connect(ui.liftoffButton, SIGNAL(clicked()), uas, SLOT(launch()));
connect(ui.landButton, SIGNAL(clicked()), uas, SLOT(home())); connect(ui.landButton, SIGNAL(clicked()), uas, SLOT(home()));
connect(ui.shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown())); connect(ui.shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));
connect(ui.setHomeButton, SIGNAL(clicked()), uas, SLOT(setLocalOriginAtCurrentGPSPosition()));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(statusChanged(int)), this, SLOT(updateState(int))); connect(uas, SIGNAL(statusChanged(int)), this, SLOT(updateState(int)));
......
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