Commit c901048a authored by Bryan Godbolt's avatar Bryan Godbolt

Merge branch 'dev' of git://github.com/pixhawk/qgroundcontrol into pix-dev

parents 5ba240ba b232d1e1
......@@ -65,7 +65,7 @@ macx {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5
DESTDIR = $$BASEDIR/bin/mac
#DESTDIR = $$BASEDIR/bin/mac
INCLUDEPATH += -framework SDL
LIBS += -framework IOKit \
......@@ -146,12 +146,12 @@ macx {
linux-g++ {
debug {
DESTDIR = $$BUILDDIR/debug
#DESTDIR = $$BUILDDIR/debug
CONFIG += debug
}
release {
DESTDIR = $$BUILDDIR/release
#DESTDIR = $$BUILDDIR/release
}
QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
......@@ -214,12 +214,12 @@ linux-g++ {
linux-g++-64 {
debug {
DESTDIR = $$BUILDDIR/debug
#DESTDIR = $$BUILDDIR/debug
CONFIG += debug
}
release {
DESTDIR = $$BUILDDIR/release
#DESTDIR = $$BUILDDIR/release
}
QMAKE_PRE_LINK += cp -rf $$BASEDIR/audio $$DESTDIR/.
......@@ -364,11 +364,11 @@ win32-g++ {
debug {
DESTDIR = $$BUILDDIR/debug
#DESTDIR = $$BUILDDIR/debug
}
release {
DESTDIR = $$BUILDDIR/release
#DESTDIR = $$BUILDDIR/release
}
RC_FILE = $$BASEDIR/qgroundcontrol.rc
......
......@@ -104,17 +104,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit processChanged(this->uasId, payload.watchdog_id, payload.process_id, payload.state, (payload.muted == 1) ? true : false, payload.crashes, payload.pid);
}
break;
case MAVLINK_MSG_ID_DEBUG_VECT:
{
mavlink_debug_vect_t vect;
mavlink_msg_debug_vect_decode(msg, &vect);
QString str((const char*)vect.name);
quint64 time = getUnixTime(vect.usec);
emit valueChanged(uasId, str+".x", vect.x, time);
emit valueChanged(uasId, str+".y", vect.y, time);
emit valueChanged(uasId, str+".z", vect.z, time);
}
break;
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
{
mavlink_vision_position_estimate_t pos;
......
......@@ -421,6 +421,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
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:
{
mavlink_rc_channels_raw_t channels;
......@@ -565,6 +572,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, severity, text);
}
break;
case MAVLINK_MSG_ID_DEBUG_VECT:
{
mavlink_debug_vect_t vect;
mavlink_msg_debug_vect_decode(&message, &vect);
QString str((const char*)vect.name);
quint64 time = getUnixTime(vect.usec);
emit valueChanged(uasId, str+".x", vect.x, time);
emit valueChanged(uasId, str+".y", vect.y, time);
emit valueChanged(uasId, str+".z", vect.z, time);
}
break;
//#ifdef MAVLINK_ENABLED_PIXHAWK
// case MAVLINK_MSG_ID_POINT_OF_INTEREST:
// {
......@@ -646,13 +664,43 @@ 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)
{
#ifdef MAVLINK_ENABLED_PIXHAWK
#ifdef MAVLINK_ENABLED_PIXHAWK
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
#endif
}
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
......@@ -1213,14 +1261,12 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
// if(mode == (int)MAV_MODE_MANUAL)
// {
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message);
qDebug() << __FILE__ << __LINE__ << ": SENT MANUAL CONTROL MESSAGE: roll" << manualRollAngle << " pitch: " << manualPitchAngle << " yaw: " << manualYawAngle << " thrust: " << manualThrust;
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
#endif
// }
}
......
......@@ -243,6 +243,8 @@ public slots:
/** @brief Update the system state */
void updateState();
/** @brief Set world frame origin at current GPS position */
void setLocalOriginAtCurrentGPSPosition();
/** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
/** @brief Add an offset in body frame to the setpoint */
......
......@@ -194,6 +194,8 @@ public slots:
//virtual void requestWaypoints() = 0;
/** @brief Clear all existing waypoints on the robot */
//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 */
virtual void requestParameters() = 0;
/** @brief Write parameter to permanent storage */
......
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>210</width>
<height>130</height>
<width>328</width>
<height>357</height>
</rect>
</property>
<property name="minimumSize">
......@@ -19,7 +19,7 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="10,10,0,10,10,5,100" columnstretch="0,0,10,10,10,0">
<layout class="QGridLayout" name="gridLayout" rowstretch="10,10,0,10,10,10,10,100" columnstretch="0,10,5,5,10,0">
<property name="margin">
<number>0</number>
</property>
......@@ -74,7 +74,7 @@
</property>
</spacer>
</item>
<item row="0" column="0" rowspan="6">
<item row="0" column="0" rowspan="7">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -91,7 +91,7 @@
<widget class="QPushButton" name="liftoffButton">
<property name="minimumSize">
<size>
<width>80</width>
<width>60</width>
<height>12</height>
</size>
</property>
......@@ -108,7 +108,7 @@
<widget class="QPushButton" name="landButton">
<property name="minimumSize">
<size>
<width>80</width>
<width>60</width>
<height>12</height>
</size>
</property>
......@@ -125,7 +125,7 @@
<widget class="QPushButton" name="shutdownButton">
<property name="minimumSize">
<size>
<width>80</width>
<width>60</width>
<height>12</height>
</size>
</property>
......@@ -138,7 +138,7 @@
</property>
</widget>
</item>
<item row="0" column="5" rowspan="6">
<item row="0" column="5" rowspan="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -178,7 +178,7 @@
</property>
</widget>
</item>
<item row="5" column="1" colspan="4">
<item row="6" column="1" colspan="4">
<widget class="QLabel" name="lastActionLabel">
<property name="minimumSize">
<size>
......@@ -194,7 +194,7 @@
</property>
</widget>
</item>
<item row="6" column="0" colspan="6">
<item row="7" column="0" colspan="6">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
......@@ -210,6 +210,23 @@
</property>
</spacer>
</item>
<item row="5" column="1" colspan="2">
<widget class="QPushButton" name="setHomeButton">
<property name="minimumSize">
<size>
<width>60</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Set Origin</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/go-home.svg</normaloff>:/images/actions/go-home.svg</iconset>
</property>
</widget>
</item>
</layout>
</widget>
<resources>
......
......@@ -95,6 +95,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch()));
disconnect(ui.landButton, SIGNAL(clicked()), oldUAS, SLOT(home()));
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(statusChanged(int)), this, SLOT(updateState(int)));
}
......@@ -104,6 +105,7 @@ void UASControlWidget::setUAS(UASInterface* uas)
connect(ui.liftoffButton, SIGNAL(clicked()), uas, SLOT(launch()));
connect(ui.landButton, SIGNAL(clicked()), uas, SLOT(home()));
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(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