Commit 1d9aa4cb authored by lm's avatar lm

Cleaned up minor things, small bugfixes

parent 6f445903
......@@ -65,7 +65,7 @@ macx {
}
} else {
# x64 Mac OS X Snow Leopard 10.6 and later
CONFIG += x86_64 x86 cocoa
CONFIG += x86_64 x86 cocoa phonon
#CONFIG -= x86 # phonon
#message(Building for Mac OS X 64bit/Snow Leopard 10.6 and later)
debug {
......
......@@ -297,9 +297,10 @@ void GAudioOutput::beep()
{
// Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav"));
qDebug() << "FILE:" << f.fileName();
m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
m_media->play();
}
}
}
void GAudioOutput::selectFemaleVoice()
......
......@@ -284,7 +284,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.x = cur->x;
PControlSetPoint.y = cur->y;
PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->yaw;
PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg);
......@@ -299,7 +299,7 @@ void MAVLinkSimulationWaypointPlanner::send_setpoint(uint16_t seq)
PControlSetPoint.x = cur->x;
PControlSetPoint.y = cur->y;
PControlSetPoint.z = cur->z;
PControlSetPoint.yaw = cur->yaw;
PControlSetPoint.yaw = cur->param4;
mavlink_msg_local_position_setpoint_set_encode(systemid, compid, &msg, &PControlSetPoint);
link->sendMAVLinkMessage(&msg);
......@@ -337,7 +337,7 @@ void MAVLinkSimulationWaypointPlanner::send_waypoint(uint8_t target_systemid, ui
wp->target_system = target_systemid;
wp->target_component = target_compid;
if (verbose) qDebug("Sent waypoint %u (%u / %u / %u / %u / %u / %f / %u / %f / %f / %u / %f / %f / %f / %f / %u)\n", wp->seq, wp->target_system, wp->target_component, wp->seq, wp->frame, wp->action, wp->orbit, wp->orbit_direction, wp->param1, wp->param2, wp->current, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue);
if (verbose) qDebug("Sent waypoint %u (%u / %u / %u / %u / %u / %f / %f / %f / %u / %f / %f / %f / %f / %u)\n", wp->seq, wp->target_system, wp->target_component, wp->seq, wp->frame, wp->action, wp->param3, wp->param1, wp->param2, wp->current, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue);
mavlink_msg_waypoint_encode(systemid, compid, &msg, wp);
link->sendMAVLinkMessage(&msg);
......@@ -502,19 +502,19 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
//compare current yaw
if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*M_PI)
{
if (att.yaw - yaw_tolerance <= wp->yaw && att.yaw + yaw_tolerance >= wp->yaw)
if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4)
yawReached = true;
}
else if(att.yaw - yaw_tolerance < 0.0f)
{
float lowerBound = 360.0f + att.yaw - yaw_tolerance;
if (lowerBound < wp->yaw || wp->yaw < att.yaw + yaw_tolerance)
if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance)
yawReached = true;
}
else
{
float upperBound = att.yaw + yaw_tolerance - 2.f*M_PI;
if (att.yaw - yaw_tolerance < wp->yaw || wp->yaw < upperBound)
if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound)
yawReached = true;
}
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
......@@ -39,20 +38,12 @@ PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) :
*/
void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t* msg = &message;
if (message.sysid == uasId)
{
// QString uasState;
// QString stateDescription;
// QString patternPath;
switch (message.msgid)
{
case MAVLINK_MSG_ID_RAW_AUX:
......@@ -156,7 +147,8 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
break;
default:
// Do nothing
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
break;
}
}
......
......@@ -192,9 +192,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
QString uasState;
QString stateDescription;
// Receive named value message
receiveMessageNamedValue(message);
switch (message.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
......@@ -223,6 +220,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit systemTypeSet(this, type);
}
break;
case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT:
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
// Receive named value message
receiveMessageNamedValue(message);
break;
case MAVLINK_MSG_ID_BOOT:
getStatusForCode((int)MAV_STATE_BOOT, uasState, stateDescription);
......@@ -237,7 +239,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// FIXME
//qDebug() << "SYSTEM NAV MODE:" << state.nav_mode;
QString audiostring = "System " + QString::number(this->getUASID());
QString audiostring = "System " + getUASName();
QString stateAudio = "";
QString modeAudio = "";
bool statechanged = false;
......@@ -277,7 +279,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mode = "GUIDED MODE";
break;
case (uint8_t)MAV_MODE_READY:
mode = "READY";
mode = "READY MODE";
break;
case (uint8_t)MAV_MODE_TEST1:
mode = "TEST1 MODE";
......@@ -748,6 +750,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_waypoint_reached_t wpr;
mavlink_msg_waypoint_reached_decode(&message, &wpr);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
GAudioOutput::instance()->say(QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq));
}
break;
......@@ -866,12 +869,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
#endif
// Messages to ignore
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET:
break;
default:
{
if (!unknownPackets.contains(message.msgid))
{
unknownPackets.append(message.msgid);
QString errString = tr("UNABLE TO DECODE MESSAGE WITH ID %1").arg(message.msgid);
QString errString = tr("UNABLE TO DECODE MESSAGE NUMBER %1").arg(message.msgid);
GAudioOutput::instance()->say(errString+tr(", please check the communication console for details."));
emit textMessageReceived(uasId, message.compid, 255, errString);
std::cout << "Unable to decode message from system " << std::dec << static_cast<int>(message.sysid) << " with message id:" << static_cast<int>(message.msgid) << std::endl;
......@@ -1928,7 +1934,7 @@ void UAS::startLowBattAlarm()
{
if (!lowBattAlarm)
{
GAudioOutput::instance()->alert("LOW BATTERY");
GAudioOutput::instance()->alert(tr("SYSTEM %1 HAS LOW BATTERY").arg(getUASName()));
QTimer::singleShot(2000, GAudioOutput::instance(), SLOT(startEmergency()));
lowBattAlarm = true;
}
......
......@@ -138,8 +138,8 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id)
{
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->yaw << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_ACTION) wp->action;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_ACTION) wp->action);
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_ACTION) wp->action;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param4, wp->autocontinue, wp->current, wp->param1, wp->param2, (MAV_FRAME) wp->frame, (MAV_ACTION) wp->action);
addWaypoint(lwp, false);
//get next waypoint
......@@ -663,8 +663,7 @@ void UASWaypointManager::writeWaypoints()
cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->orbit = cur_s->getLoiterOrbit();
cur_d->orbit_direction = 0;
cur_d->param3 = cur_s->getLoiterOrbit();
cur_d->param1 = cur_s->getParam1();
cur_d->param2 = cur_s->getParam2();
cur_d->frame = cur_s->getFrame();
......@@ -673,7 +672,7 @@ void UASWaypointManager::writeWaypoints()
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ();
cur_d->yaw = cur_s->getYaw();
cur_d->param4 = cur_s->getYaw();
if (cur_s->getCurrent() && noCurrent)
noCurrent = false;
......
......@@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>237</width>
<width>307</width>
<height>221</height>
</rect>
</property>
......@@ -134,7 +134,7 @@
<item row="1" column="1">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Extended</string>
<string>Ext. Status</string>
</property>
</widget>
</item>
......@@ -148,7 +148,7 @@
<item row="5" column="1">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Controller</string>
<string>Raw Contr.</string>
</property>
</widget>
</item>
......@@ -183,7 +183,7 @@
<item row="0" column="3">
<widget class="QLabel" name="label_5">
<property name="text">
<string>RC Values</string>
<string>RC Chan.</string>
</property>
</widget>
</item>
......
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