Newer
Older
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @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>
#ifndef M_PI
#define M_PI 3.14159265358979323846
#endif
#include "WaypointView.h"
#include "ui_WaypointView.h"
WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
QWidget(parent),
m_ui(new Ui::WaypointView)
{
m_ui->setupUi(this);
this->wp = wp;
wp->setFrame(MAV_FRAME_LOCAL);
// add actions
m_ui->comboBox_action->addItem("Navigate",MAV_ACTION_NAVIGATE);
m_ui->comboBox_action->addItem("TakeOff",MAV_ACTION_TAKEOFF);
m_ui->comboBox_action->addItem("Land",MAV_ACTION_LAND);
m_ui->comboBox_action->addItem("Loiter",MAV_ACTION_LOITER);
// add frames
m_ui->comboBox_frame->addItem("Global",MAV_FRAME_GLOBAL);
m_ui->comboBox_frame->addItem("Local",MAV_FRAME_LOCAL);
// defaults
changedAction(0);
changedFrame(0);
updateValues();
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(setOrbit(double)));
connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
}
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;
}
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
void WaypointView::changedAction(int index)
{
// set action for waypoint
// hide everything to start
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
// set waypoint action
MAV_ACTION action = (MAV_ACTION)m_ui->comboBox_action->itemData(index).toUInt();
wp->setAction(action);
// expose ui based on action
switch(action)
{
case MAV_ACTION_TAKEOFF:
m_ui->takeOffAngleSpinBox->show();
break;
case MAV_ACTION_LAND:
break;
case MAV_ACTION_NAVIGATE:
m_ui->autoContinue->show();
break;
case MAV_ACTION_LOITER:
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
break;
default:
std::cerr << "unknown action" << std::endl;
}
}
void WaypointView::changedFrame(int index)
{
// hide everything to start
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
// set waypoint action
MAV_FRAME frame = (MAV_FRAME)m_ui->comboBox_frame->itemData(index).toUInt();
wp->setFrame(frame);
switch(frame)
{
case MAV_FRAME_GLOBAL:
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
break;
case MAV_FRAME_LOCAL:
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
break;
default:
std::cerr << "unknown frame" << std::endl;
}
}
//m_ui->selectedBox->setChecked(true);
//m_ui->selectedBox->setCheckState(Qt::Checked);
//wp->setCurrent(false);
//wp->setCurrent(true);
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
void WaypointView::updateValues()
{
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
// update frame
MAV_FRAME frame = wp->getFrame();
changedFrame(m_ui->comboBox_frame->findData(frame));
switch(frame)
{
case(MAV_FRAME_LOCAL):
m_ui->posNSpinBox->setValue(wp->getX());
m_ui->posESpinBox->setValue(wp->getY());
m_ui->posDSpinBox->setValue(wp->getZ());
break;
case(MAV_FRAME_GLOBAL):
m_ui->lonSpinBox->setValue(wp->getX());
m_ui->latSpinBox->setValue(wp->getY());
m_ui->altSpinBox->setValue(wp->getZ());
break;
}
// update action
MAV_ACTION action = wp->getAction();
changedFrame(m_ui->comboBox_frame->findData(frame));
changedAction(m_ui->comboBox_action->findData(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;
}
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue());
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\
m_ui->orbitSpinBox->setValue(wp->getOrbit());
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
}
}
else
{
m_ui->selectedBox->setCheckState(Qt::Unchecked);
}