Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
94947491
Commit
94947491
authored
Jan 22, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed last wp issue
parent
247042fd
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
184 additions
and
123 deletions
+184
-123
qgroundcontrol.pro
qgroundcontrol.pro
+0
-1
Waypoint.cc
src/Waypoint.cc
+54
-54
Waypoint.h
src/Waypoint.h
+24
-24
MapWidget.cc
src/ui/MapWidget.cc
+4
-0
WaypointView.cc
src/ui/WaypointView.cc
+56
-44
WaypointView.ui
src/ui/WaypointView.ui
+45
-0
MAV2DIcon.cc
src/ui/map/MAV2DIcon.cc
+1
-0
No files found.
qgroundcontrol.pro
View file @
94947491
...
...
@@ -140,7 +140,6 @@ FORMS += src/ui/MainWindow.ui \
src
/
ui
/
QGCPxImuFirmwareUpdate
.
ui
\
src
/
ui
/
QGCDataPlot2D
.
ui
\
src
/
ui
/
QGCRemoteControlView
.
ui
\
src
/
ui
/
WaypointGlobalView
.
ui
\
src
/
ui
/
QMap3D
.
ui
\
src
/
ui
/
QGCWebView
.
ui
\
src
/
ui
/
map3D
/
QGCGoogleEarthView
.
ui
\
...
...
src/Waypoint.cc
View file @
94947491
...
...
@@ -9,15 +9,15 @@ This file is part of the QGROUNDCONTROL project
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.
QGROUNDCONTROL 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 QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
...
...
@@ -32,7 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <QStringList>
Waypoint
::
Waypoint
(
quint16
_id
,
float
_x
,
float
_y
,
float
_z
,
float
_yaw
,
bool
_autocontinue
,
bool
_current
,
float
_orbit
,
int
_holdTime
,
MAV_FRAME
_frame
,
MAV_ACTION
_action
)
Waypoint
::
Waypoint
(
quint16
_id
,
double
_x
,
double
_y
,
double
_z
,
double
_yaw
,
bool
_autocontinue
,
bool
_current
,
double
_orbit
,
int
_holdTime
,
MAV_FRAME
_frame
,
MAV_ACTION
_action
)
:
id
(
_id
),
x
(
_x
),
y
(
_y
),
...
...
@@ -50,7 +50,7 @@ Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _
Waypoint
::~
Waypoint
()
{
}
void
Waypoint
::
save
(
QTextStream
&
saveStream
)
...
...
@@ -94,7 +94,7 @@ void Waypoint::setId(quint16 id)
emit
changed
(
this
);
}
void
Waypoint
::
setX
(
float
x
)
void
Waypoint
::
setX
(
double
x
)
{
if
(
this
->
x
!=
x
)
{
...
...
@@ -103,7 +103,7 @@ void Waypoint::setX(float x)
}
}
void
Waypoint
::
setY
(
float
y
)
void
Waypoint
::
setY
(
double
y
)
{
if
(
this
->
y
!=
y
)
{
...
...
@@ -112,7 +112,7 @@ void Waypoint::setY(float y)
}
}
void
Waypoint
::
setZ
(
float
z
)
void
Waypoint
::
setZ
(
double
z
)
{
if
(
this
->
z
!=
z
)
{
...
...
@@ -121,7 +121,7 @@ void Waypoint::setZ(float z)
}
}
void
Waypoint
::
setYaw
(
float
yaw
)
void
Waypoint
::
setYaw
(
double
yaw
)
{
if
(
this
->
yaw
!=
yaw
)
{
...
...
@@ -166,7 +166,7 @@ void Waypoint::setCurrent(bool current)
}
}
void
Waypoint
::
setOrbit
(
float
orbit
)
void
Waypoint
::
setOrbit
(
double
orbit
)
{
if
(
this
->
orbit
!=
orbit
)
{
...
...
@@ -184,47 +184,47 @@ void Waypoint::setHoldTime(int holdTime)
}
}
void
Waypoint
::
setX
(
double
x
)
{
if
(
this
->
x
!=
static_cast
<
float
>
(
x
))
{
this
->
x
=
x
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setY
(
double
y
)
{
if
(
this
->
y
!=
static_cast
<
float
>
(
y
))
{
this
->
y
=
y
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setZ
(
double
z
)
{
if
(
this
->
z
!=
static_cast
<
float
>
(
z
))
{
this
->
z
=
z
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setYaw
(
double
yaw
)
{
if
(
this
->
yaw
!=
static_cast
<
float
>
(
yaw
))
{
this
->
yaw
=
yaw
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setOrbit
(
double
orbit
)
{
if
(
this
->
orbit
!=
static_cast
<
float
>
(
orbit
))
{
this
->
orbit
=
orbit
;
emit
changed
(
this
);
}
}
//
void Waypoint::setX(double x)
//
{
// if (this->x != static_cast<double
>(x))
//
{
//
this->x = x;
//
emit changed(this);
//
}
//
}
//
void Waypoint::setY(double y)
//
{
// if (this->y != static_cast<double
>(y))
//
{
//
this->y = y;
//
emit changed(this);
//
}
//
}
//
void Waypoint::setZ(double z)
//
{
// if (this->z != static_cast<double
>(z))
//
{
//
this->z = z;
//
emit changed(this);
//
}
//
}
//
void Waypoint::setYaw(double yaw)
//
{
// if (this->yaw != static_cast<double
>(yaw))
//
{
//
this->yaw = yaw;
//
emit changed(this);
//
}
//
}
//
void Waypoint::setOrbit(double orbit)
//
{
// if (this->orbit != static_cast<double
>(orbit))
//
{
//
this->orbit = orbit;
//
emit changed(this);
//
}
//
}
src/Waypoint.h
View file @
94947491
...
...
@@ -43,20 +43,20 @@ class Waypoint : public QObject
Q_OBJECT
public:
Waypoint
(
quint16
id
=
0
,
float
x
=
0
.
0
f
,
float
y
=
0
.
0
f
,
float
z
=
0
.
0
f
,
float
yaw
=
0
.
0
f
,
bool
autocontinue
=
false
,
bool
current
=
false
,
float
orbit
=
0
.
15
f
,
int
holdTime
=
0
,
Waypoint
(
quint16
id
=
0
,
double
x
=
0
.
0
f
,
double
y
=
0
.
0
f
,
double
z
=
0
.
0
f
,
double
yaw
=
0
.
0
f
,
bool
autocontinue
=
false
,
bool
current
=
false
,
double
orbit
=
0
.
15
f
,
int
holdTime
=
0
,
MAV_FRAME
frame
=
MAV_FRAME_GLOBAL
,
MAV_ACTION
action
=
MAV_ACTION_NAVIGATE
);
~
Waypoint
();
quint16
getId
()
const
{
return
id
;
}
float
getX
()
const
{
return
x
;
}
float
getY
()
const
{
return
y
;
}
float
getZ
()
const
{
return
z
;
}
float
getYaw
()
const
{
return
yaw
;
}
double
getX
()
const
{
return
x
;
}
double
getY
()
const
{
return
y
;
}
double
getZ
()
const
{
return
z
;
}
double
getYaw
()
const
{
return
yaw
;
}
bool
getAutoContinue
()
const
{
return
autocontinue
;
}
bool
getCurrent
()
const
{
return
current
;
}
float
getOrbit
()
const
{
return
orbit
;
}
float
getHoldTime
()
const
{
return
holdTime
;
}
double
getOrbit
()
const
{
return
orbit
;
}
double
getHoldTime
()
const
{
return
holdTime
;
}
MAV_FRAME
getFrame
()
const
{
return
frame
;
}
MAV_ACTION
getAction
()
const
{
return
action
;
}
const
QString
&
getName
()
const
{
return
name
;
}
...
...
@@ -67,38 +67,38 @@ public:
protected:
quint16
id
;
float
x
;
float
y
;
float
z
;
float
yaw
;
double
x
;
double
y
;
double
z
;
double
yaw
;
MAV_FRAME
frame
;
MAV_ACTION
action
;
bool
autocontinue
;
bool
current
;
float
orbit
;
double
orbit
;
int
holdTime
;
QString
name
;
public
slots
:
void
setId
(
quint16
id
);
void
setX
(
float
x
);
void
setY
(
float
y
);
void
setZ
(
float
z
);
void
setYaw
(
float
yaw
);
void
setX
(
double
x
);
void
setY
(
double
y
);
void
setZ
(
double
z
);
void
setYaw
(
double
yaw
);
void
setAction
(
MAV_ACTION
action
);
void
setFrame
(
MAV_FRAME
frame
);
void
setAutocontinue
(
bool
autoContinue
);
void
setCurrent
(
bool
current
);
void
setOrbit
(
float
orbit
);
void
setOrbit
(
double
orbit
);
void
setHoldTime
(
int
holdTime
);
//for QDoubleSpin
void
setX
(
double
x
);
void
setY
(
double
y
);
void
setZ
(
double
z
);
void
setYaw
(
double
yaw
);
void
setOrbit
(
double
orbit
);
//
//for QDoubleSpin
//
void setX(double x);
//
void setY(double y);
//
void setZ(double z);
//
void setYaw(double yaw);
//
void setOrbit(double orbit);
signals:
/** @brief Announces a change to the waypoint data */
...
...
src/ui/MapWidget.cc
View file @
94947491
...
...
@@ -930,6 +930,7 @@ void MapWidget::changeEvent(QEvent *e)
void
MapWidget
::
clearWaypoints
(
int
uas
)
{
Q_UNUSED
(
uas
);
// Clear the previous WP track
//mc->layer("Waypoints")->clearGeometries();
...
...
@@ -962,6 +963,7 @@ void MapWidget::clearWaypoints(int uas)
void
MapWidget
::
clearPath
(
int
uas
)
{
Q_UNUSED
(
uas
);
mc
->
layer
(
"Tracking"
)
->
clearGeometries
();
foreach
(
qmapcontrol
::
LineString
*
ls
,
uasTrails
)
{
...
...
@@ -976,6 +978,8 @@ void MapWidget::clearPath(int uas)
void
MapWidget
::
updateCameraPosition
(
double
radio
,
double
bearing
,
QString
dir
)
{
Q_UNUSED
(
dir
);
Q_UNUSED
(
bearing
);
// FIXME Mariano
//camPoints.clear();
QPointF
currentPos
=
mc
->
currentCoordinate
();
...
...
src/ui/WaypointView.cc
View file @
94947491
/*=====================================================================
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/>.
/*===================================================================
======================================================================*/
/**
...
...
@@ -43,8 +23,8 @@ This file is part of the PIXHAWK project
#include "ui_WaypointView.h"
WaypointView
::
WaypointView
(
Waypoint
*
wp
,
QWidget
*
parent
)
:
QWidget
(
parent
),
m_ui
(
new
Ui
::
WaypointView
)
QWidget
(
parent
),
m_ui
(
new
Ui
::
WaypointView
)
{
m_ui
->
setupUi
(
this
);
...
...
@@ -146,7 +126,7 @@ void WaypointView::changedAction(int index)
break
;
case
MAV_ACTION_NAVIGATE
:
m_ui
->
autoContinue
->
show
();
m_ui
->
orbitSpinBox
->
show
();
m_ui
->
orbitSpinBox
->
show
();
break
;
case
MAV_ACTION_LOITER
:
m_ui
->
orbitSpinBox
->
show
();
...
...
@@ -159,14 +139,6 @@ void WaypointView::changedAction(int index)
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
);
...
...
@@ -174,11 +146,17 @@ void WaypointView::changedFrame(int index)
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
();
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
();
...
...
@@ -217,14 +195,36 @@ void WaypointView::updateValues()
switch
(
frame
)
{
case
(
MAV_FRAME_LOCAL
):
m_ui
->
posNSpinBox
->
setValue
(
wp
->
getX
());
m_ui
->
posESpinBox
->
setValue
(
wp
->
getY
());
m_ui
->
posDSpinBox
->
setValue
(
wp
->
getZ
());
{
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
):
m_ui
->
lonSpinBox
->
setValue
(
wp
->
getX
());
m_ui
->
latSpinBox
->
setValue
(
wp
->
getY
());
m_ui
->
altSpinBox
->
setValue
(
wp
->
getZ
());
{
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
());
}
}
break
;
}
changedFrame
(
frame_index
);
...
...
@@ -232,7 +232,10 @@ void WaypointView::updateValues()
// update action
MAV_ACTION
action
=
wp
->
getAction
();
int
action_index
=
m_ui
->
comboBox_action
->
findData
(
action
);
m_ui
->
comboBox_action
->
setCurrentIndex
(
action_index
);
if
(
m_ui
->
comboBox_action
->
currentIndex
()
!=
action_index
)
{
m_ui
->
comboBox_action
->
setCurrentIndex
(
action_index
);
}
switch
(
action
)
{
case
MAV_ACTION_TAKEOFF
:
...
...
@@ -248,12 +251,21 @@ void WaypointView::updateValues()
}
changedAction
(
action_index
);
m_ui
->
yawSpinBox
->
setValue
(
wp
->
getYaw
()
/
M_PI
*
180.
);
if
(
m_ui
->
yawSpinBox
->
value
()
!=
wp
->
getYaw
()
/
M_PI
*
180.
)
{
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
());
m_ui
->
idLabel
->
setText
(
QString
(
"%1"
).
arg
(
wp
->
getId
()));
if
(
m_ui
->
orbitSpinBox
->
value
()
!=
wp
->
getOrbit
())
{
m_ui
->
orbitSpinBox
->
setValue
(
wp
->
getOrbit
());
}
if
(
m_ui
->
holdTimeSpinBox
->
value
()
!=
wp
->
getHoldTime
())
{
m_ui
->
holdTimeSpinBox
->
setValue
(
wp
->
getHoldTime
());
}
wp
->
blockSignals
(
false
);
}
...
...
@@ -265,7 +277,7 @@ void WaypointView::setCurrent(bool state)
}
else
{
m_ui
->
selectedBox
->
setCheckState
(
Qt
::
Unchecked
);
m_ui
->
selectedBox
->
setCheckState
(
Qt
::
Unchecked
);
}
}
...
...
src/ui/WaypointView.ui
View file @
94947491
...
...
@@ -170,6 +170,9 @@ QProgressBar::chunk#thrustBar {
</property>
<item>
<widget
class=
"QCheckBox"
name=
"selectedBox"
>
<property
name=
"focusPolicy"
>
<enum>
Qt::TabFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Currently selected waypoint
</string>
</property>
...
...
@@ -231,12 +234,21 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::ClickFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position X coordinate
</string>
</property>
<property
name=
"wrapping"
>
<bool>
false
</bool>
</property>
<property
name=
"frame"
>
<bool>
true
</bool>
</property>
<property
name=
"accelerated"
>
<bool>
true
</bool>
</property>
<property
name=
"prefix"
>
<string>
N
</string>
</property>
...
...
@@ -262,6 +274,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position Y coordinate
</string>
</property>
...
...
@@ -293,6 +308,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position Z coordinate (negative)
</string>
</property>
...
...
@@ -321,6 +339,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"prefix"
>
<string>
lat
</string>
</property>
...
...
@@ -349,6 +370,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"prefix"
>
<string>
lon
</string>
</property>
...
...
@@ -402,6 +426,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Yaw angle
</string>
</property>
...
...
@@ -430,6 +457,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Orbit radius
</string>
</property>
...
...
@@ -458,6 +488,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Time in milliseconds that the MAV has to stay inside the orbit before advancing
</string>
</property>
...
...
@@ -486,6 +519,9 @@ QProgressBar::chunk#thrustBar {
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Take off angle
</string>
</property>
...
...
@@ -515,6 +551,9 @@ QProgressBar::chunk#thrustBar {
<height>
22
</height>
</size>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::NoFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Move Up
</string>
</property>
...
...
@@ -535,6 +574,9 @@ QProgressBar::chunk#thrustBar {
<height>
22
</height>
</size>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::NoFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Move Down
</string>
</property>
...
...
@@ -555,6 +597,9 @@ QProgressBar::chunk#thrustBar {
<height>
22
</height>
</size>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::NoFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Delete
</string>
</property>
...
...
src/ui/map/MAV2DIcon.cc
View file @
94947491
...
...
@@ -57,6 +57,7 @@ void MAV2DIcon::setYaw(float yaw)
void
MAV2DIcon
::
drawIcon
(
QPen
*
pen
)
{
Q_UNUSED
(
pen
);
switch
(
type
)
{
case
MAV_ICON_GENERIC
:
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment