Commit d88602e1 authored by lm's avatar lm

Fixed WP interface

parent 216295e7
......@@ -32,19 +32,20 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <QStringList>
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _yaw, bool _autocontinue, bool _current, double _orbit, int _holdTime, MAV_FRAME _frame, MAV_CMD _action)
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1, double _param2, double _param3, double _param4,
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action)
: id(_id),
x(_x),
y(_y),
z(_z),
yaw(_yaw),
yaw(_param4),
frame(_frame),
action(_action),
autocontinue(_autocontinue),
current(_current),
orbit(0),
param1(_orbit),
param2(_holdTime),
orbit(_param3),
param1(_param1),
param2(_param2),
name(QString("WP%1").arg(id, 2, 10, QChar('0')))
{
}
......@@ -154,6 +155,15 @@ void Waypoint::setAltitude(double altitude)
}
}
void Waypoint::setYaw(int yaw)
{
if (this->yaw != yaw)
{
this->yaw = yaw;
emit changed(this);
}
}
void Waypoint::setYaw(double yaw)
{
if (this->yaw != yaw)
......@@ -298,6 +308,15 @@ void Waypoint::setHoldTime(int holdTime)
}
}
void Waypoint::setHoldTime(double holdTime)
{
if (this->param1 != holdTime)
{
this->param1 = holdTime;
emit changed(this);
}
}
void Waypoint::setTurns(int turns)
{
if (this->param1 != turns)
......
......@@ -43,9 +43,8 @@ class Waypoint : public QObject
Q_OBJECT
public:
Waypoint(quint16 id = 0, double x = 0.0f, double y = 0.0f, double z = 0.0f, double yaw = 0.0f, bool autocontinue = false,
bool current = false, double orbit = 0.15f, int holdTime = 0,
MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
Waypoint(quint16 id = 0, double x = 0.0, double y = 0.0, double z = 0.0, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0,
bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
~Waypoint();
quint16 getId() const { return id; }
......@@ -101,6 +100,9 @@ public slots:
void setLatitude(double lat);
void setLongitude(double lon);
void setAltitude(double alt);
/** @brief Yaw angle in COMPASS DEGREES: 0-360 */
void setYaw(int yaw);
/** @brief Yaw angle in COMPASS DEGREES: 0-360 */
void setYaw(double yaw);
/** @brief Set the waypoint action */
void setAction(int action);
......@@ -118,6 +120,7 @@ public slots:
void setParam7(double param7);
void setAcceptanceRadius(double radius);
void setHoldTime(int holdTime);
void setHoldTime(double holdTime);
/** @brief Number of turns for loiter waypoints */
void setTurns(int turns);
......
......@@ -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->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << (MAV_FRAME) wp->frame << (MAV_CMD) wp->command;
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_CMD) wp->command);
//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_CMD) wp->command;
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->param1, wp->param2, wp->param3, wp->param4, wp->autocontinue, wp->current, (MAV_FRAME) wp->frame, (MAV_CMD) wp->command);
addWaypoint(lwp, false);
//get next waypoint
......@@ -665,16 +665,16 @@ 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->param3 = cur_s->getLoiterOrbit();
cur_d->param1 = cur_s->getParam1();
cur_d->param2 = cur_s->getParam2();
cur_d->param3 = cur_s->getParam3();
cur_d->param4 = cur_s->getParam4();
cur_d->frame = cur_s->getFrame();
cur_d->command = cur_s->getAction();
cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ();
cur_d->param4 = cur_s->getYaw();
if (cur_s->getCurrent() && noCurrent)
noCurrent = false;
......
......@@ -181,14 +181,14 @@ void WaypointList::add()
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getAcceptanceRadius(),
last->getHoldTime(), last->getFrame(), last->getAction());
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getParam1(), last->getParam2(), last->getParam3(), last->getParam4(),
last->getAutoContinue(), false, last->getFrame(), last->getAction());
uas->getWaypointManager()->addWaypoint(wp);
}
else
{
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0.0, true, true, 0.15, 0, MAV_FRAME_GLOBAL, MAV_CMD_NAV_WAYPOINT);
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0.0, 0.0, 0.0, 0.0, true, true, MAV_FRAME_GLOBAL, MAV_CMD_NAV_WAYPOINT);
uas->getWaypointManager()->addWaypoint(wp);
}
}
......
......@@ -68,10 +68,6 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
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)));
......@@ -79,10 +75,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->lonSpinBox, 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->yawSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setYaw(int)));
connect(m_ui->upButton, SIGNAL(clicked()), this, SLOT(moveUp()));
connect(m_ui->downButton, SIGNAL(clicked()), this, SLOT(moveDown()));
......@@ -95,7 +88,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
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->holdTimeSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setHoldTime(double)));
connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int)));
connect(m_ui->takeOffAngleSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
......@@ -110,11 +103,6 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(customCommand->param7SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam7(double)));
}
void WaypointView::setYaw(int yawDegree)
{
emit setYaw((double)yawDegree*M_PI/180.);
}
void WaypointView::moveUp()
{
emit moveUpWaypoint(wp);
......@@ -179,7 +167,7 @@ void WaypointView::updateActionView(int action)
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->holdTimeSpinBox->show();
m_ui->customActionWidget->hide();
m_ui->autoContinue->show();
......@@ -459,9 +447,9 @@ void WaypointView::updateValues()
std::cerr << "unknown action" << std::endl;
}
if (m_ui->yawSpinBox->value() != wp->getYaw()/M_PI*180.)
if (m_ui->yawSpinBox->value() != wp->getYaw())
{
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->yawSpinBox->setValue(wp->getYaw());
}
if (m_ui->selectedBox->isChecked() != wp->getCurrent())
{
......
......@@ -73,8 +73,6 @@ public slots:
void changedCurrent(int);
void updateValues(void);
void setYaw(int); //hidden degree to radian conversion
protected slots:
void changeViewMode(QGC_WAYPOINTVIEW_MODE mode);
......
......@@ -161,7 +161,7 @@ QProgressBar::chunk#thrustBar {
<property name="title">
<string/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="1,1,2,6,10,10,10,10,10,10,1,4,4,4,2,4,1,1,1,1,1">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="1,1,1,1,20,20,20,20,20,20,1,8,8,1,4,8,1,1,1,1,1">
<property name="spacing">
<number>2</number>
</property>
......@@ -512,10 +512,10 @@ QProgressBar::chunk#thrustBar {
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Orbit (navigate waypoint) /Loiter (loiter waypoint) radius</string>
<string>Loiter radius</string>
</property>
<property name="statusTip">
<string>Orbit (navigate waypoint) /Loiter (loiter waypoint) radius</string>
<string>Loiter radius</string>
</property>
<property name="suffix">
<string> m</string>
......@@ -536,6 +536,13 @@ QProgressBar::chunk#thrustBar {
</item>
<item>
<widget class="QDoubleSpinBox" name="acceptanceSpinBox">
<property name="toolTip">
<string>Uncertainty radius in meters
where to accept this waypoint as reached</string>
</property>
<property name="statusTip">
<string>Uncertainty radius in meters where to accept this waypoint as reached</string>
</property>
<property name="suffix">
<string> m</string>
</property>
......@@ -545,33 +552,19 @@ QProgressBar::chunk#thrustBar {
</widget>
</item>
<item>
<widget class="QSpinBox" name="holdTimeSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<widget class="QDoubleSpinBox" name="holdTimeSpinBox">
<property name="toolTip">
<string>Time in milliseconds that the MAV has to stay inside the orbit before advancing</string>
<string>Rotaty wing and ground vehicles only:
Time to stay at this position before advancing</string>
</property>
<property name="statusTip">
<string>Time in milliseconds that the MAV has to stay inside the orbit before advancing</string>
<string>Rotaty wing and ground vehicles only: Time to stay at this position before advancing</string>
</property>
<property name="suffix">
<string> ms</string>
<string> s</string>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>500</number>
</property>
<property name="value">
<number>0</number>
<double>9999.989999999999782</double>
</property>
</widget>
</item>
......@@ -611,6 +604,9 @@ QProgressBar::chunk#thrustBar {
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>0</number>
</property>
</widget>
</item>
<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