Newer
Older
/*===================================================================
======================================================================*/
/**
* @file
* @brief Displays one waypoint
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
#include <cmath>
#include <qmath.h>
#include "ui_QGCCustomWaypointAction.h"
customCommand(new Ui_QGCCustomWaypointAction),
// CUSTOM COMMAND WIDGET
customCommand->setupUi(m_ui->customActionWidget);
m_ui->comboBox_action->addItem(tr("Navigate"),MAV_ACTION_NAVIGATE);
m_ui->comboBox_action->addItem(tr("TakeOff"),MAV_ACTION_TAKEOFF);
m_ui->comboBox_action->addItem(tr("Loiter Unlim."),MAV_ACTION_LOITER);
m_ui->comboBox_action->addItem(tr("Loiter Time"),MAV_ACTION_LOITER_MAX_TIME);
m_ui->comboBox_action->addItem(tr("Loiter Turns"),MAV_ACTION_LOITER_MAX_TURNS);
m_ui->comboBox_action->addItem(tr("Return to Launch"),MAV_ACTION_RETURN);
m_ui->comboBox_action->addItem(tr("Land"),MAV_ACTION_LAND);
m_ui->comboBox_action->addItem(tr("Other"), MAV_ACTION_NB);
// m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND);
// m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE);
// m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE);
// m_ui->comboBox_action->addItem(tr("Relay ON"), MAV_ACTION_RELAY_ON);
// m_ui->comboBox_action->addItem(tr("Relay OFF"), MAV_ACTION_RELAY_OFF);
// add frames
m_ui->comboBox_frame->addItem("Global",MAV_FRAME_GLOBAL);
m_ui->comboBox_frame->addItem("Local",MAV_FRAME_LOCAL);
m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION);
// Initialize view correctly
updateActionView(wp->getAction());
updateFrameView(wp->getFrame());
updateValues();
// Check for mission frame
if (wp->getFrame() == MAV_FRAME_MISSION)
{
m_ui->comboBox_action->setCurrentIndex(m_ui->comboBox_action->count()-1);
}
// defaults
//changedAction(wp->getAction());
//changedFrame(wp->getFrame());
connect(m_ui->posNSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->posESpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->posDSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(m_ui->lonSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->altSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
//hidden degree to radian conversion of the yaw angle
connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYaw(int)));
connect(this, SIGNAL(setYaw(double)), wp, SLOT(setYaw(double)));
connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp()));
connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown()));
connect(m_ui->removeButton, SIGNAL(clicked()), this, SLOT(remove()));
connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int)));
connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
connect(m_ui->comboBox_action, SIGNAL(activated(int)), this, SLOT(changedAction(int)));
connect(m_ui->comboBox_frame, SIGNAL(activated(int)), this, SLOT(changedFrame(int)));
connect(m_ui->orbitSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setLoiterOrbit(double)));
connect(m_ui->acceptanceSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setAcceptanceRadius(double)));
connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int)));
// Connect actions
connect(customCommand->commandSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setAction(int)));
connect(customCommand->param1SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
connect(customCommand->param2SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam2(double)));
connect(customCommand->param3SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam3(double)));
connect(customCommand->param4SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam4(double)));
// MISSION ELEMENT WIDGET
// TODO
}
void WaypointView::setYaw(int yawDegree)
{
emit setYaw((double)yawDegree*M_PI/180.);
}
void WaypointView::moveUp()
{
emit moveUpWaypoint(wp);
}
void WaypointView::moveDown()
{
emit moveDownWaypoint(wp);
}
void WaypointView::remove()
{
emit removeWaypoint(wp);
delete this;
}
void WaypointView::updateActionView(int action)
{
// expose ui based on action
switch(action)
{
case MAV_ACTION_TAKEOFF:
m_ui->orbitSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->takeOffAngleSpinBox->show();
break;
case MAV_ACTION_LAND:
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
break;
case MAV_ACTION_RETURN:
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
break;
case MAV_ACTION_NAVIGATE:
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->acceptanceSpinBox->show();
m_ui->yawSpinBox->show();
break;
case MAV_ACTION_LOITER:
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->orbitSpinBox->show();
break;
case MAV_ACTION_LOITER_MAX_TURNS:
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->orbitSpinBox->show();
m_ui->turnsSpinBox->show();
break;
case MAV_ACTION_LOITER_MAX_TIME:
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
break;
default:
/**
* @param index The index of the combo box of the action entry, NOT the action ID
*/
void WaypointView::changedAction(int index)
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
int actionIndex = m_ui->comboBox_action->itemData(index).toUInt();
if (actionIndex < MAV_ACTION_NB && actionIndex >= 0)
{
MAV_ACTION action = (MAV_ACTION) actionIndex;
wp->setAction(action);
}
// Expose ui based on action
// Change to mission frame
// if action is unknown
switch(actionIndex)
{
case MAV_ACTION_TAKEOFF:
case MAV_ACTION_LAND:
case MAV_ACTION_RETURN:
case MAV_ACTION_NAVIGATE:
case MAV_ACTION_LOITER:
case MAV_ACTION_LOITER_MAX_TURNS:
case MAV_ACTION_LOITER_MAX_TIME:
case MAV_ACTION_DELAY_BEFORE_COMMAND:
case MAV_ACTION_CHANGE_MODE:
case MAV_ACTION_SET_ORIGIN:
case MAV_ACTION_RELAY_ON:
case MAV_ACTION_RELAY_OFF:
// Back to global frame
if (wp->getFrame() == MAV_FRAME_MISSION) changedFrame(0);
// Update view
updateActionView(actionIndex);
break;
case MAV_ACTION_NB:
default:
// Switch to mission frame
changedFrame(MAV_FRAME_MISSION);
wp->setFrame(MAV_FRAME_MISSION);
break;
}
}
void WaypointView::updateFrameView(int frame)
{
switch(frame)
{
case MAV_FRAME_GLOBAL:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_LOCAL:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_MISSION:
// Hide almost everything
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posNSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->comboBox_frame->hide();
// Show action widget
if (!m_ui->customActionWidget->isVisible())
{
m_ui->customActionWidget->show();
}
if (!m_ui->autoContinue->isVisible())
{
m_ui->autoContinue->show();
}
break;
default:
std::cerr << "unknown frame" << std::endl;
}
}
void WaypointView::changedFrame(int index)
{
// set waypoint action
MAV_FRAME frame = (MAV_FRAME)m_ui->comboBox_frame->itemData(index).toUInt();
wp->setFrame(frame);
updateFrameView(frame);
}
m_ui->selectedBox->setChecked(true);
m_ui->selectedBox->setCheckState(Qt::Checked);
wp->setCurrent(false);
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
void WaypointView::updateValues()
{
// Deactivate signals from the WP
wp->blockSignals(true);
// update frame
MAV_FRAME frame = wp->getFrame();
int frame_index = m_ui->comboBox_frame->findData(frame);
if (m_ui->comboBox_frame->currentIndex() != frame_index)
{
m_ui->comboBox_frame->setCurrentIndex(frame_index);
updateFrameView(frame);
switch(frame)
{
case(MAV_FRAME_LOCAL):
{
if (m_ui->posNSpinBox->value() != wp->getX())
{
m_ui->posNSpinBox->setValue(wp->getX());
}
if (m_ui->posESpinBox->value() != wp->getY())
{
m_ui->posESpinBox->setValue(wp->getY());
}
if (m_ui->posDSpinBox->value() != wp->getZ())
{
m_ui->posDSpinBox->setValue(wp->getZ());
}
}
break;
case(MAV_FRAME_GLOBAL):
{
if (m_ui->lonSpinBox->value() != wp->getX())
{
m_ui->lonSpinBox->setValue(wp->getX());
}
if (m_ui->latSpinBox->value() != wp->getY())
{
m_ui->latSpinBox->setValue(wp->getY());
}
if (m_ui->altSpinBox->value() != wp->getZ())
{
m_ui->altSpinBox->setValue(wp->getZ());
}
}
case (MAV_FRAME_MISSION):
{
// TODO Change to mission view
}
break;
MAV_ACTION action = wp->getAction();
int action_index = m_ui->comboBox_action->findData(action);
// Set to "Other" action if it was -1
if (action_index == -1)
{
action_index = m_ui->comboBox_action->findData(MAV_ACTION_NB);
}
// Only update if changed
if (m_ui->comboBox_action->currentIndex() != action_index)
{
// TODO Action and frame should not be coupled
if (wp->getFrame() != MAV_FRAME_MISSION)
{
m_ui->comboBox_action->setCurrentIndex(action_index);
updateActionView(action);
}
switch(action)
{
case MAV_ACTION_TAKEOFF:
break;
case MAV_ACTION_LAND:
break;
case MAV_ACTION_NAVIGATE:
break;
case MAV_ACTION_LOITER:
break;
default:
std::cerr << "unknown action" << std::endl;
}
if (m_ui->yawSpinBox->value() != wp->getYaw()/M_PI*180.)
{
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
}
if (m_ui->selectedBox->isChecked() != wp->getCurrent())
{
m_ui->selectedBox->setChecked(wp->getCurrent());
}
if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
{
m_ui->autoContinue->setChecked(wp->getAutoContinue());
}
if (m_ui->orbitSpinBox->value() != wp->getLoiterOrbit())
m_ui->orbitSpinBox->setValue(wp->getLoiterOrbit());
}
if (m_ui->acceptanceSpinBox->value() != wp->getAcceptanceRadius())
{
m_ui->acceptanceSpinBox->setValue(wp->getAcceptanceRadius());
}
if (m_ui->holdTimeSpinBox->value() != wp->getHoldTime())
{
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
}
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
// UPDATE CUSTOM ACTION WIDGET
qDebug() << "UPDATING CUSTOM ACTION WIDGET";
if (customCommand->commandSpinBox->value() != wp->getAction())
{
customCommand->commandSpinBox->setValue(wp->getAction());
qDebug() << "Changed action";
}
// Param 1
if (customCommand->param1SpinBox->value() != wp->getParam1())
{
customCommand->param1SpinBox->setValue(wp->getParam1());
}
// Param 2
if (customCommand->param2SpinBox->value() != wp->getParam2())
{
customCommand->param2SpinBox->setValue(wp->getParam2());
}
// Param 3
if (customCommand->param3SpinBox->value() != wp->getParam3())
{
customCommand->param3SpinBox->setValue(wp->getParam3());
}
// Param 4
if (customCommand->param4SpinBox->value() != wp->getParam4())
{
customCommand->param4SpinBox->setValue(wp->getParam4());
}