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
3a7c76ea
Commit
3a7c76ea
authored
Dec 07, 2010
by
tecnosapiens
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
change and connect signal from SlugPadCameraControl to SlugsVideoCamControl
parent
3d2817be
Changes
12
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
1385 additions
and
1207 deletions
+1385
-1207
SlugsDataSensorView.cc
src/ui/SlugsDataSensorView.cc
+6
-0
SlugsDataSensorView.h
src/ui/SlugsDataSensorView.h
+8
-0
SlugsDataSensorView.ui
src/ui/SlugsDataSensorView.ui
+1
-1
SlugsPIDControl.cpp
src/ui/SlugsPIDControl.cpp
+101
-0
SlugsPIDControl.h
src/ui/SlugsPIDControl.h
+22
-0
SlugsPIDControl.ui
src/ui/SlugsPIDControl.ui
+912
-879
SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp
+219
-2
SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h
+26
-1
SlugsPadCameraControl.ui
src/ui/SlugsPadCameraControl.ui
+32
-2
SlugsVideoCamControl.cpp
src/ui/SlugsVideoCamControl.cpp
+43
-282
SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h
+14
-16
SlugsVideoCamControl.ui
src/ui/SlugsVideoCamControl.ui
+1
-24
No files found.
src/ui/SlugsDataSensorView.cc
View file @
3a7c76ea
...
...
@@ -15,6 +15,10 @@ SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
activeUAS
=
NULL
;
this
->
setVisible
(
false
);
}
SlugsDataSensorView
::~
SlugsDataSensorView
()
...
...
@@ -236,4 +240,6 @@ void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
ui
->
m_GpsSat
->
setText
(
QString
::
number
(
gpsDateTime
.
visSat
));
}
#endif // MAVLINK_ENABLED_SLUGS
src/ui/SlugsDataSensorView.h
View file @
3a7c76ea
...
...
@@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsMAV.h"
#include "mavlink.h"
namespace
Ui
{
class
SlugsDataSensorView
;
}
...
...
@@ -163,6 +164,8 @@ public slots:
void
slugsGPSDateTimeChanged
(
int
systemId
,
const
mavlink_gps_date_time_t
&
gpsDateTime
);
#endif // MAVLINK_ENABLED_SLUGS
protected:
...
...
@@ -172,6 +175,11 @@ private:
Ui
::
SlugsDataSensorView
*
ui
;
};
#endif // SLUGSDATASENSORVIEW_H
src/ui/SlugsDataSensorView.ui
View file @
3a7c76ea
...
...
@@ -35,7 +35,7 @@
<item>
<widget
class=
"QTabWidget"
name=
"SlugsSensorView_tabWidget"
>
<property
name=
"currentIndex"
>
<number>
2
</number>
<number>
0
</number>
</property>
<widget
class=
"QWidget"
name=
"tab"
>
<attribute
name=
"title"
>
...
...
src/ui/SlugsPIDControl.cpp
View file @
3a7c76ea
...
...
@@ -22,6 +22,19 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
setRedColorStyle
();
setGreenColorStyle
();
refreshTimerGet
=
new
QTimer
(
this
);
refreshTimerGet
->
setInterval
(
100
);
// 20 Hz
connect
(
refreshTimerGet
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
slugsGetGeneral
()));
refreshTimerSet
=
new
QTimer
(
this
);
refreshTimerSet
->
setInterval
(
100
);
// 20 Hz
connect
(
refreshTimerSet
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
slugsSetGeneral
()));
counterRefreshGet
=
1
;
counterRefreshSet
=
1
;
}
/**
...
...
@@ -40,6 +53,8 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
connect
(
slugsMav
,
SIGNAL
(
slugsActionAck
(
int
,
const
mavlink_action_ack_t
&
)),
this
,
SLOT
(
recibeMensaje
(
int
,
mavlink_action_ack_t
)));
connect
(
slugsMav
,
SIGNAL
(
slugsPidValues
(
int
,
mavlink_pid_t
)),
this
,
SLOT
(
receivePidValues
(
int
,
mavlink_pid_t
))
);
connect
(
ui
->
setGeneral_pushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
slugsTimerStartSet
()));
}
#endif // MAVLINK_ENABLED_SLUG
...
...
@@ -611,4 +626,90 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
void
SlugsPIDControl
::
slugsGetGeneral
()
{
valuesMutex
.
lock
();
switch
(
counterRefreshGet
)
{
case
1
:
ui
->
dT_PID_get_pushButton
->
click
();
break
;
case
2
:
ui
->
HELPComm_PDI_get_pushButton
->
click
();
break
;
case
3
:
ui
->
dE_PID_get_pushButton
->
click
();
break
;
case
4
:
ui
->
dR_PDI_get_pushButton
->
click
();
break
;
case
5
:
ui
->
dA_PID_get_pushButton
->
click
();
break
;
case
6
:
ui
->
Pitch2dT_PDI_get_pushButton
->
click
();
break
;
default:
refreshTimerGet
->
stop
();
break
;
}
counterRefreshGet
++
;
valuesMutex
.
unlock
();
}
void
SlugsPIDControl
::
slugsSetGeneral
()
{
valuesMutex
.
lock
();
switch
(
counterRefreshSet
)
{
case
1
:
ui
->
dT_PID_set_pushButton
->
click
();
break
;
case
2
:
ui
->
HELPComm_PDI_set_pushButton
->
click
();
break
;
case
3
:
ui
->
dE_PID_set_pushButton
->
click
();
break
;
case
4
:
ui
->
dR_PDI_set_pushButton
->
click
();
break
;
case
5
:
ui
->
dA_PID_set_pushButton
->
click
();
break
;
case
6
:
ui
->
Pitch2dT_PDI_set_pushButton
->
click
();
break
;
default:
refreshTimerSet
->
stop
();
break
;
}
counterRefreshSet
++
;
valuesMutex
.
unlock
();
}
void
SlugsPIDControl
::
slugsTimerStartSet
()
{
counterRefreshSet
=
1
;
refreshTimerSet
->
start
();
}
void
SlugsPIDControl
::
slugsTimerStartGet
()
{
counterRefreshGet
=
1
;
refreshTimerGet
->
start
();
}
void
SlugsPIDControl
::
slugsTimerStop
()
{
// refreshTimerGet->stop();
// counterRefresh = 1;
}
#endif // MAVLINK_ENABLED_SLUGS
src/ui/SlugsPIDControl.h
View file @
3a7c76ea
...
...
@@ -7,6 +7,8 @@
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
#include "mavlink.h"
#include <QTimer>
#include <QMutex>
namespace
Ui
{
class
SlugsPIDControl
;
...
...
@@ -236,6 +238,20 @@ public slots:
*/
void
get_Pitch2dT_PID
();
/**
* @brief get and updates the values on widget
*/
void
slugsGetGeneral
();
/**
* @brief Sent all values to UAS
*/
void
slugsSetGeneral
();
void
slugsTimerStartSet
();
void
slugsTimerStartGet
();
void
slugsTimerStop
();
//Create, send and get Messages PID
// void createMessagePID();
...
...
@@ -263,6 +279,12 @@ private:
//SlugsMav Message
mavlink_pid_t
pidMessage
;
mavlink_slugs_action_t
actionSlugs
;
QTimer
*
refreshTimerSet
;
///< The main timer, controls the update view
QTimer
*
refreshTimerGet
;
///< The main timer, controls the update view
int
counterRefreshSet
;
int
counterRefreshGet
;
QMutex
valuesMutex
;
};
#endif // SLUGSPIDCONTROL_H
src/ui/SlugsPIDControl.ui
View file @
3a7c76ea
This diff is collapsed.
Click to expand it.
src/ui/SlugsPadCameraControl.cpp
View file @
3a7c76ea
#include "SlugsPadCameraControl.h"
#include "ui_SlugsPadCameraControl.h"
#include <QMouseEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
SlugsPadCameraControl
::
SlugsPadCameraControl
(
QWidget
*
parent
)
:
QWidget
(
parent
),
ui
(
new
Ui
::
SlugsPadCameraControl
)
QWidget
(
parent
),
//QGraphicsView(parent),
ui
(
new
Ui
::
SlugsPadCameraControl
),
dragging
(
0
)
{
ui
->
setupUi
(
this
);
x1
=
0
;
y1
=
0
;
}
SlugsPadCameraControl
::~
SlugsPadCameraControl
()
{
delete
ui
;
}
void
SlugsPadCameraControl
::
mouseMoveEvent
(
QMouseEvent
*
event
)
{
emit
mouseMoveCoord
(
event
->
x
(),
event
->
y
());
}
void
SlugsPadCameraControl
::
mousePressEvent
(
QMouseEvent
*
event
)
{
emit
mousePressCoord
(
event
->
x
(),
event
->
y
());
x1
=
event
->
x
();
y1
=
event
->
y
();
}
void
SlugsPadCameraControl
::
mouseReleaseEvent
(
QMouseEvent
*
event
)
{
emit
mouseReleaseCoord
(
event
->
x
(),
event
->
y
());
getDeltaPositionPad
(
event
->
x
(),
event
->
y
());
}
void
SlugsPadCameraControl
::
paintEvent
(
QPaintEvent
*
pe
)
{
Q_UNUSED
(
pe
);
QPainter
painter
(
this
);
painter
.
setPen
(
Qt
::
blue
);
painter
.
setFont
(
QFont
(
"Arial"
,
30
));
// QRectF rectangle(tL.x(), tL.y(), ui->padCamContro_frame->width(), ui->padCamContro_frame->height());
// int startAngle = 30 * 16;
// int spanAngle = 120 * 16;
painter
.
drawLine
(
QPoint
(
ui
->
frame
->
width
()
/
2
,
ui
->
frame
->
geometry
().
topLeft
().
y
()),
QPoint
(
ui
->
frame
->
width
()
/
2
,
ui
->
frame
->
geometry
().
bottomRight
().
y
()));
painter
.
drawLine
(
QPoint
(
ui
->
frame
->
geometry
().
topLeft
().
x
(),
ui
->
frame
->
height
()
/
2
),
QPoint
(
ui
->
frame
->
geometry
().
bottomRight
().
x
(),
ui
->
frame
->
height
()
/
2
));
// painter.drawLine(QPoint());
//painter.drawLines(padLines);
// painter.drawPie(rectangle, startAngle, spanAngle);
//painter.drawText(rect(), Qt::AlignCenter, "Qt");
}
void
SlugsPadCameraControl
::
getDeltaPositionPad
(
int
x2
,
int
y2
)
{
QString
dir
=
"nd"
;
QPointF
localMeasures
=
ObtenerMarcacionDistanciaPixel
(
y1
,
x1
,
y2
,
x2
);
double
bearing
=
localMeasures
.
x
();
double
dist
=
getDistPixel
(
y1
,
x1
,
y2
,
x2
);
if
(((
bearing
>
330
)
&&
(
bearing
<
360
))
||
((
bearing
>=
0
)
&&
(
bearing
<=
30
)))
{
emit
dirCursorText
(
"up"
);
//bearing = 315;
dir
=
"up"
;
}
else
{
if
((
bearing
>
30
)
&&
(
bearing
<=
60
)
)
{
emit
dirCursorText
(
"right up"
);
//bearing = 315;
dir
=
"riht up"
;
}
else
{
if
((
bearing
>
60
)
&&
(
bearing
<=
105
)
)
{
emit
dirCursorText
(
"right"
);
//bearing = 315;
dir
=
"riht"
;
}
else
{
if
((
bearing
>
105
)
&&
(
bearing
<=
150
)
)
{
emit
dirCursorText
(
"right down"
);
//bearing = 315;
dir
=
"riht down"
;
}
else
{
if
((
bearing
>
150
)
&&
(
bearing
<=
195
)
)
{
emit
dirCursorText
(
"down"
);
//bearing = 315;
dir
=
"down"
;
}
else
{
if
((
bearing
>
195
)
&&
(
bearing
<=
240
)
)
{
emit
dirCursorText
(
"left down"
);
//bearing = 315;
dir
=
"left down"
;
}
else
{
if
((
bearing
>
240
)
&&
(
bearing
<=
300
)
)
{
emit
dirCursorText
(
"left"
);
//bearing = 315;
dir
=
"left"
;
}
else
{
if
((
bearing
>
300
)
&&
(
bearing
<=
330
)
)
{
emit
dirCursorText
(
"left up"
);
//bearing = 315;
dir
=
"left up"
;
}
}
}
}
}
}
}
}
emit
changeCursorPosition
(
bearing
,
dist
,
dir
);
}
double
SlugsPadCameraControl
::
getDistPixel
(
int
x1
,
int
y1
,
int
x2
,
int
y2
)
{
double
cateto_opuesto
,
cateto_adyacente
;
//latitud y longitud del primer punto
cateto_opuesto
=
abs
((
x1
-
x2
));
//diferencia de latitudes entre PCR1 y PCR2
cateto_adyacente
=
abs
((
y1
-
y2
));
//diferencia de longitudes entre PCR1 y PCR2
return
sqrt
(
pow
(
cateto_opuesto
,
2
)
+
pow
(
cateto_adyacente
,
2
));
// distancia = (float) hipotenusa;
}
/**
* Esta funcin xxxxxxxxx
* @param double lat1 -->
* @param double lon1 -->
* @param double lat2 -->
* @param double lon2 -->
* @param ref double rumbo -->
* @param ref double distancia -->
*/
QPointF
SlugsPadCameraControl
::
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
)
{
double
cateto_opuesto
,
cateto_adyacente
,
hipotenusa
,
distancia
,
marcacion
;
//latitude and longitude first point
if
(
lat1
<
0
)
lat1
=
lat1
*
(
-
1
);
if
(
lat2
<
0
)
lat2
=
lat2
*
(
-
1
);
if
(
lon1
<
0
)
lon1
=
lon1
*
(
-
1
);
if
(
lon2
<
0
)
lon1
=
lon1
*
(
-
1
);
cateto_opuesto
=
abs
((
lat1
-
lat2
));
cateto_adyacente
=
abs
((
lon1
-
lon2
));
hipotenusa
=
sqrt
(
pow
(
cateto_opuesto
,
2
)
+
pow
(
cateto_adyacente
,
2
));
distancia
=
hipotenusa
*
60
;
if
((
lat1
<
lat2
)
&&
(
lon1
>
lon2
))
//primer cuadrante
marcacion
=
360
-
((
asin
(
cateto_adyacente
/
hipotenusa
))
/
0.017453292
);
else
if
((
lat1
<
lat2
)
&&
(
lon1
<
lon2
))
//segundo cuadrante
marcacion
=
(
asin
(
cateto_adyacente
/
hipotenusa
))
/
0.017453292
;
else
if
((
lat1
>
lat2
)
&&
(
lon1
<
lon2
))
//tercer cuadrante
marcacion
=
180
-
((
asin
(
cateto_adyacente
/
hipotenusa
))
/
0.017453292
);
else
if
((
lat1
>
lat2
)
&&
(
lon1
>
lon2
))
//cuarto cuadrante
marcacion
=
180
+
((
asin
(
cateto_adyacente
/
hipotenusa
))
/
0.017453292
);
else
if
((
lat1
<
lat2
)
&&
(
lon1
==
lon2
))
//360
marcacion
=
360
;
else
if
((
lat1
==
lat2
)
&&
(
lon1
>
lon2
))
//270
marcacion
=
270
;
else
if
((
lat1
>
lat2
)
&&
(
lon1
==
lon2
))
//180
marcacion
=
180
;
else
if
((
lat1
==
lat2
)
&&
(
lon1
<
lon2
))
//90
marcacion
=
90
;
else
if
((
lat1
==
lat2
)
&&
(
lon1
==
lon2
))
//0
marcacion
=
0.0
;
// this only convert real bearing to frame widget bearing
marcacion
=
marcacion
+
90
;
if
(
marcacion
>=
360
)
marcacion
=
marcacion
-
360
;
return
QPointF
(
marcacion
,
distancia
);
}
src/ui/SlugsPadCameraControl.h
View file @
3a7c76ea
...
...
@@ -2,21 +2,46 @@
#define SLUGSPADCAMERACONTROL_H
#include <QWidget>
#include <QGraphicsView>
namespace
Ui
{
class
SlugsPadCameraControl
;
}
class
SlugsPadCameraControl
:
public
QWidget
class
SlugsPadCameraControl
:
public
QWidget
//QGraphicsView//
{
Q_OBJECT
public:
explicit
SlugsPadCameraControl
(
QWidget
*
parent
=
0
);
~
SlugsPadCameraControl
();
public
slots
:
void
getDeltaPositionPad
(
int
x
,
int
y
);
double
getDistPixel
(
int
x1
,
int
y1
,
int
x2
,
int
y2
);
QPointF
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
);
signals:
void
mouseMoveCoord
(
int
x
,
int
y
);
void
mousePressCoord
(
int
x
,
int
y
);
void
mouseReleaseCoord
(
int
x
,
int
y
);
void
dirCursorText
(
QString
dir
);
void
distance_Bearing
(
double
dist
,
double
bearing
);
void
changeCursorPosition
(
double
bearing
,
double
distance
,
QString
textDir
);
protected:
void
mousePressEvent
(
QMouseEvent
*
event
);
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
void
paintEvent
(
QPaintEvent
*
pe
);
private:
Ui
::
SlugsPadCameraControl
*
ui
;
bool
dragging
;
int
x1
;
int
y1
;
};
#endif // SLUGSPADCAMERACONTROL_H
src/ui/SlugsPadCameraControl.ui
View file @
3a7c76ea
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
400
</width>
<height>
300
</height>
<width>
183
</width>
<height>
127
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -16,6 +16,36 @@
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgb(255, 170, 0);
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<property
name=
"margin"
>
<number>
1
</number>
</property>
<property
name=
"spacing"
>
<number>
1
</number>
</property>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QFrame"
name=
"frame"
>
<property
name=
"minimumSize"
>
<size>
<width>
181
</width>
<height>
125
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgba(255, 0, 0,50%);
</string>
</property>
<property
name=
"frameShape"
>
<enum>
QFrame::StyledPanel
</enum>
</property>
<property
name=
"frameShadow"
>
<enum>
QFrame::Raised
</enum>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
...
...
src/ui/SlugsVideoCamControl.cpp
View file @
3a7c76ea
This diff is collapsed.
Click to expand it.
src/ui/SlugsVideoCamControl.h
View file @
3a7c76ea
...
...
@@ -7,6 +7,8 @@
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#include "SlugsPadCameraControl.h"
#include <QPushButton>
#define DELTA 1000
...
...
@@ -26,33 +28,29 @@ public:
public
slots
:
void
changeViewCamBorderAtMapStatus
(
bool
status
);
void
getDeltaPositionPad
(
int
x
,
int
y
);
double
getDistPixel
(
int
x1
,
int
y1
,
int
x2
,
int
y2
);
QPointF
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
);
void
getDeltaPositionPad
(
double
dir
,
double
dist
,
QString
dirText
);
void
mousePadPressEvent
(
int
x
,
int
y
);
void
mousePadReleaseEvent
(
int
x
,
int
y
);
void
mousePadMoveEvent
(
int
x
,
int
y
);
signals:
void
changeCamPosition
(
double
dist
,
double
dir
,
QString
textDir
);
void
viewCamBorderAtMap
(
bool
status
);
protected:
virtual
void
mousePressEvent
(
QMouseEvent
*
event
);
virtual
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
//virtual void paintEvent(QPaintEvent *pe);
void
paintEvent
(
QPaintEvent
*
pe
);
void
mousePressEvent
(
QMouseEvent
*
event
);
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
private:
Ui
::
SlugsVideoCamControl
*
ui
;
bool
dragging
;
int
x1
;
int
y1
;
QPoint
tL
;
QPoint
bR
;
SlugsPadCameraControl
*
padCamera
;
private:
Ui
::
SlugsVideoCamControl
*
ui
;
SlugsPadCameraControl
*
padCamera
;
};
...
...
src/ui/SlugsVideoCamControl.ui
View file @
3a7c76ea
...
...
@@ -24,29 +24,6 @@
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QFrame"
name=
"padCamContro_frame"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
false
</bool>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgba(255, 170, 0,0%);
</string>
</property>
<property
name=
"frameShape"
>
<enum>
QFrame::WinPanel
</enum>
</property>
<property
name=
"frameShadow"
>
<enum>
QFrame::Sunken
</enum>
</property>
</widget>
</item>
<item
row=
"1"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"label_x"
>
...
...
@@ -77,7 +54,7 @@
</item>
</layout>
</item>
<item
row=
"
2
"
column=
"0"
>
<item
row=
"
1
"
column=
"0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QCheckBox"
name=
"viewCamBordeatMap_checkBox"
>
...
...
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