Browse Source

Change so Waypoints are the same across maps, and offline waypoints get appeneded to the end of the MAV's waypoint list on connect

QGC4.4
Michael Carpenter 12 years ago
parent
commit
1413557255
  1. 26
      files/ardupilotmega/fixed_wing/widgets/ardupilot-heading-pid.qgw
  2. 1
      src/main.cc
  3. 33
      src/uas/UASManager.cc
  4. 7
      src/uas/UASManager.h
  5. 6
      src/ui/MainWindow.cc
  6. 2
      src/ui/designer/QGCComboBox.cc
  7. 2
      src/ui/designer/QGCParamSlider.cc
  8. 94
      src/ui/map/QGCMapWidget.cc
  9. 1
      src/ui/map/QGCMapWidget.h

26
files/ardupilotmega/fixed_wing/widgets/ardupilot-heading-pid.qgw

@ -1,26 +0,0 @@
[Heading%20PID%20Tuning]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading D Gain
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_D
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_P
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=5
QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Gain
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_I
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Heading I Limit
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=HDNG2RLL_IMAX
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=200
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=3000
QGC_TOOL_WIDGET_ITEMS\size=4

1
src/main.cc

@ -64,7 +64,6 @@ void msgHandler( QtMsgType type, const char* msg )
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
// install the message handler // install the message handler
#ifdef Q_OS_WIN #ifdef Q_OS_WIN
qInstallMsgHandler( msgHandler ); qInstallMsgHandler( msgHandler );

33
src/uas/UASManager.cc

@ -235,7 +235,8 @@ UASManager::UASManager() :
homeLat(47.3769), homeLat(47.3769),
homeLon(8.549444), homeLon(8.549444),
homeAlt(470.0), homeAlt(470.0),
homeFrame(MAV_FRAME_GLOBAL) homeFrame(MAV_FRAME_GLOBAL),
offlineUASWaypointManager(NULL)
{ {
loadSettings(); loadSettings();
setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1); setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);
@ -280,6 +281,22 @@ void UASManager::addUAS(UASInterface* uas)
if (firstUAS) if (firstUAS)
{ {
setActiveUAS(uas); setActiveUAS(uas);
if (offlineUASWaypointManager->getWaypointEditableList().size() > 0)
{
if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<offlineUASWaypointManager->getWaypointEditableList().size();i++)
{
Waypoint *wp = uas->getWaypointManager()->createWaypoint();
wp->setLatitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(offlineUASWaypointManager->getWaypointEditableList()[i]->getAltitude());
}
}
offlineUASWaypointManager->deleteLater();
offlineUASWaypointManager = 0;
}
} }
} }
@ -336,6 +353,20 @@ UASInterface* UASManager::silentGetActiveUAS()
{ {
return activeUAS; ///< Return zero pointer if no UAS has been loaded return activeUAS; ///< Return zero pointer if no UAS has been loaded
} }
UASWaypointManager *UASManager::getActiveUASWaypointManager()
{
if (activeUAS)
{
return activeUAS->getWaypointManager();
}
if (!offlineUASWaypointManager)
{
offlineUASWaypointManager = new UASWaypointManager(NULL);
}
return offlineUASWaypointManager;
}
bool UASManager::launchActiveUAS() bool UASManager::launchActiveUAS()
{ {

7
src/uas/UASManager.h

@ -58,6 +58,12 @@ public:
* @return NULL pointer if no UAS exists, active UAS else * @return NULL pointer if no UAS exists, active UAS else
**/ **/
UASInterface* getActiveUAS(); UASInterface* getActiveUAS();
/**
* @brief getActiveUASWaypointManager
* @return uas->getUASWaypointManager(), or if not connected, a singleton instance of a UASWaypointManager.
*/
UASWaypointManager *getActiveUASWaypointManager();
UASInterface* silentGetActiveUAS(); UASInterface* silentGetActiveUAS();
/** /**
* @brief Get the UAS with this id * @brief Get the UAS with this id
@ -244,6 +250,7 @@ protected:
UASManager(); UASManager();
QList<UASInterface*> systems; QList<UASInterface*> systems;
UASInterface* activeUAS; UASInterface* activeUAS;
UASWaypointManager *offlineUASWaypointManager;
QMutex activeUASMutex; QMutex activeUASMutex;
double homeLat; double homeLat;
double homeLon; double homeLon;

6
src/ui/MainWindow.cc

@ -1711,7 +1711,7 @@ void MainWindow::UASCreated(UASInterface* uas)
// Load last view if setting is present // Load last view if setting is present
if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED")) if (settings.contains("CURRENT_VIEW_WITH_UAS_CONNECTED"))
{ {
int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt(); /*int view = settings.value("CURRENT_VIEW_WITH_UAS_CONNECTED").toInt();
switch (view) switch (view)
{ {
case VIEW_ENGINEER: case VIEW_ENGINEER:
@ -1736,11 +1736,11 @@ void MainWindow::UASCreated(UASInterface* uas)
default: default:
loadOperatorView(); loadOperatorView();
break; break;
} }*/
} }
else else
{ {
loadOperatorView(); // loadOperatorView();
} }
} }

2
src/ui/designer/QGCComboBox.cc

@ -154,7 +154,7 @@ void QGCComboBox::selectParameter(int paramIndex)
if (uas->getParamManager()) if (uas->getParamManager())
{ {
// Current value // Current value
uas->getParamManager()->requestParameterUpdate(component, parameterName); //uas->getParamManager()->requestParameterUpdate(component, parameterName);
// Minimum // Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName)) if (uas->getParamManager()->isParamMinKnown(parameterName))

2
src/ui/designer/QGCParamSlider.cc

@ -184,7 +184,7 @@ void QGCParamSlider::selectParameter(int paramIndex)
if (uas->getParamManager()) if (uas->getParamManager())
{ {
// Current value // Current value
uas->getParamManager()->requestParameterUpdate(component, parameterName); //uas->getParamManager()->requestParameterUpdate(component, parameterName);
// Minimum // Minimum
if (uas->getParamManager()->isParamMinKnown(parameterName)) if (uas->getParamManager()->isParamMinKnown(parameterName))

94
src/ui/map/QGCMapWidget.cc

@ -9,7 +9,6 @@
QGCMapWidget::QGCMapWidget(QWidget *parent) : QGCMapWidget::QGCMapWidget(QWidget *parent) :
mapcontrol::OPMapWidget(parent), mapcontrol::OPMapWidget(parent),
currWPManager(NULL),
firingWaypointChange(NULL), firingWaypointChange(NULL),
maxUpdateInterval(2.1f), // 2 seconds maxUpdateInterval(2.1f), // 2 seconds
followUAVEnabled(false), followUAVEnabled(false),
@ -17,17 +16,42 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
trailInterval(2.0f), trailInterval(2.0f),
followUAVID(0), followUAVID(0),
mapInitialized(false), mapInitialized(false),
homeAltitude(0) homeAltitude(0),
uas(0)
{ {
//currWPManager = new UASWaypointManager(NULL); //Create a waypoint manager that is null.
currWPManager = UASManager::instance()->getActiveUASWaypointManager();
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
offlineMode = true;
// Widget is inactive until shown // Widget is inactive until shown
defaultGuidedAlt = -1; defaultGuidedAlt = -1;
loadSettings(false); loadSettings(false);
this->setContextMenuPolicy(Qt::ActionsContextMenu); this->setContextMenuPolicy(Qt::ActionsContextMenu);
QAction *guidedaction = new QAction(this);
guidedaction->setText("Go To Here (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered()));
this->addAction(guidedaction);
guidedaction = new QAction(this);
guidedaction->setText("Go To Here Alt (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
this->addAction(guidedaction);
QAction *cameraaction = new QAction(this);
cameraaction->setText("Point Camera Here");
connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
this->addAction(cameraaction);
} }
void QGCMapWidget::guidedActionTriggered() void QGCMapWidget::guidedActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return;
}
if (currWPManager) if (currWPManager)
{ {
if (defaultGuidedAlt == -1) if (defaultGuidedAlt == -1)
@ -49,6 +73,11 @@ void QGCMapWidget::guidedActionTriggered()
} }
bool QGCMapWidget::guidedAltActionTriggered() bool QGCMapWidget::guidedAltActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return false;
}
bool ok = false; bool ok = false;
int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok); int tmpalt = QInputDialog::getInt(this,"Altitude","Enter default altitude (in meters) of destination point for guided mode",100,0,30000,1,&ok);
if (!ok) if (!ok)
@ -62,6 +91,11 @@ bool QGCMapWidget::guidedAltActionTriggered()
} }
void QGCMapWidget::cameraActionTriggered() void QGCMapWidget::cameraActionTriggered()
{ {
if (!uas)
{
QMessageBox::information(0,"Error","Please connect first");
return;
}
ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas); ArduPilotMegaMAV *newmav = qobject_cast<ArduPilotMegaMAV*>(this->uas);
if (newmav) if (newmav)
{ {
@ -262,32 +296,14 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
if (uas) if (uas)
{ {
//UASWaypointManager *old = currWPManager;
currWPManager = uas->getWaypointManager(); currWPManager = uas->getWaypointManager();
QList<QAction*> actionList = this->actions();
for (int i=0;i<actionList.size();i++) updateSelectedSystem(uas->getUASID());
{ followUAVID = uas->getUASID();
this->removeAction(actionList[i]);
actionList[i]->deleteLater(); updateWaypointList(uas->getUASID());
}
if (currWPManager->guidedModeSupported())
{
QAction *guidedaction = new QAction(this);
guidedaction->setText("Go To Here (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedActionTriggered()));
this->addAction(guidedaction);
guidedaction = new QAction(this);
guidedaction->setText("Go To Here Alt (Guided Mode)");
connect(guidedaction,SIGNAL(triggered()),this,SLOT(guidedAltActionTriggered()));
this->addAction(guidedaction);
if (uas->getAutopilotType() == MAV_AUTOPILOT_ARDUPILOTMEGA)
{
QAction *cameraaction = new QAction(this);
cameraaction->setText("Point Camera Here");
connect(cameraaction,SIGNAL(triggered()),this,SLOT(cameraActionTriggered()));
this->addAction(cameraaction);
}
}
// Connect the waypoint manager / data storage to the UI // Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
@ -295,11 +311,27 @@ void QGCMapWidget::activeUASSet(UASInterface* uas)
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)));
updateSelectedSystem(uas->getUASID()); /*if (offlineMode)
followUAVID = uas->getUASID(); {
if (QMessageBox::question(0,"Question","Do you want to append the offline waypoints to the ones currently on the UAV?",QMessageBox::Yes,QMessageBox::No) == QMessageBox::Yes)
{
//Need to transfer all waypoints from the offline mode WPManager to the online mode.
for (int i=0;i<old->getWaypointEditableList().size();i++)
{
Waypoint *wp = currWPManager->createWaypoint();
wp->setLatitude(old->getWaypointEditableList()[i]->getLatitude());
wp->setLongitude(old->getWaypointEditableList()[i]->getLongitude());
wp->setAltitude(old->getWaypointEditableList()[i]->getAltitude());
}
}
offlineMode = false;
old->deleteLater();
}*/
// Delete all waypoints and add waypoint from new system // Delete all waypoints and add waypoint from new system
updateWaypointList(uas->getUASID());
} }
} }
@ -563,7 +595,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
// Currently only accept waypoint updates from the UAS in focus // Currently only accept waypoint updates from the UAS in focus
// this has to be changed to accept read-only updates from other systems as well. // this has to be changed to accept read-only updates from other systems as well.
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas); UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (uasInstance->getWaypointManager() == currWPManager || uas == -1) if (!uasInstance || uasInstance->getWaypointManager() == currWPManager || uas == -1)
{ {
// Only accept waypoints in global coordinate frame // Only accept waypoints in global coordinate frame
if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType()) if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())

1
src/ui/map/QGCMapWidget.h

@ -137,6 +137,7 @@ protected:
void mouseDoubleClickEvent(QMouseEvent* event); void mouseDoubleClickEvent(QMouseEvent* event);
UASWaypointManager* currWPManager; ///< The current waypoint manager UASWaypointManager* currWPManager; ///< The current waypoint manager
bool offlineMode;
QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons; QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons;
QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints; QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints;
Waypoint* firingWaypointChange; Waypoint* firingWaypointChange;

Loading…
Cancel
Save