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
eff0195a
Commit
eff0195a
authored
Dec 15, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'experimental' of
git://github.com/tecnosapiens/qgroundcontrol
into mergeRemote
parents
a7688a04
02c420a7
Changes
7
Show whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
1548 additions
and
1563 deletions
+1548
-1563
SlugsMAV.cc
src/uas/SlugsMAV.cc
+3
-3
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+6
-1
SlugsDataSensorView.cc
src/ui/SlugsDataSensorView.cc
+2
-2
SlugsDataSensorView.ui
src/ui/SlugsDataSensorView.ui
+1510
-1522
SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp
+12
-20
SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h
+4
-0
SlugsVideoCamControl.ui
src/ui/SlugsVideoCamControl.ui
+11
-15
No files found.
src/uas/SlugsMAV.cc
View file @
eff0195a
...
@@ -137,7 +137,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -137,7 +137,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
case
MAVLINK_MSG_ID_PID
:
//182
case
MAVLINK_MSG_ID_PID
:
//182
memset
(
&
mlSinglePid
,
0
,
sizeof
(
mavlink_pid_t
));
memset
(
&
mlSinglePid
,
0
,
sizeof
(
mavlink_pid_t
));
mavlink_msg_pid_decode
(
&
message
,
&
mlSinglePid
);
mavlink_msg_pid_decode
(
&
message
,
&
mlSinglePid
);
qDebug
()
<<
"
\n
SLUGS RECEIVED PID Message = "
<<
mlSinglePid
.
idx
;
//
qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
...
@@ -220,7 +220,7 @@ void SlugsMAV::emitSignals (void){
...
@@ -220,7 +220,7 @@ void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
#ifdef MAVLINK_ENABLED_SLUGS
void
SlugsMAV
::
emitGpsSignals
(
void
){
void
SlugsMAV
::
emitGpsSignals
(
void
){
qDebug
()
<<
"After Emit GPS Signal"
<<
mlGpsData
.
fix_type
;
//
qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
//ToDo Uncomment if. it was comment only to test
//ToDo Uncomment if. it was comment only to test
...
@@ -248,7 +248,7 @@ void SlugsMAV::emitGpsSignals (void){
...
@@ -248,7 +248,7 @@ void SlugsMAV::emitGpsSignals (void){
void
SlugsMAV
::
emitPidSignal
()
void
SlugsMAV
::
emitPidSignal
()
{
{
qDebug
()
<<
"
\n
SLUGS RECEIVED PID Message"
;
//
qDebug() << "\nSLUGS RECEIVED PID Message";
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
emit
slugsPidValues
(
uasId
,
mlSinglePid
);
}
}
...
...
src/uas/UASWaypointManager.cc
View file @
eff0195a
...
@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASWaypointManager.h"
#include "UASWaypointManager.h"
#include "UAS.h"
#include "UAS.h"
#include "mavlink_types.h"
#define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_TIMEOUT_MS 2000 ///< maximum time to wait for pending messages until timeout
#define PROTOCOL_DELAY_MS 40 ///< minimum delay between sent messages
#define PROTOCOL_DELAY_MS 40 ///< minimum delay between sent messages
...
@@ -600,22 +601,26 @@ void UASWaypointManager::sendWaypointRequest(quint16 seq)
...
@@ -600,22 +601,26 @@ void UASWaypointManager::sendWaypointRequest(quint16 seq)
void
UASWaypointManager
::
sendWaypoint
(
quint16
seq
)
void
UASWaypointManager
::
sendWaypoint
(
quint16
seq
)
{
{
mavlink_message_t
message
;
mavlink_message_t
message
;
qDebug
()
<<
" WP Buffer count: "
<<
waypoint_buffer
.
count
();
if
(
seq
<
waypoint_buffer
.
count
())
if
(
seq
<
waypoint_buffer
.
count
())
{
{
mavlink_waypoint_t
*
wp
;
mavlink_waypoint_t
*
wp
;
wp
=
waypoint_buffer
.
at
(
seq
);
wp
=
waypoint_buffer
.
at
(
seq
);
wp
->
target_system
=
uas
.
getUASID
();
wp
->
target_system
=
uas
.
getUASID
();
wp
->
target_component
=
MAV_COMP_ID_WAYPOINTPLANNER
;
wp
->
target_component
=
MAV_COMP_ID_WAYPOINTPLANNER
;
emit
updateStatusString
(
QString
(
"sending waypoint ID %1 of %2 total"
).
arg
(
wp
->
seq
).
arg
(
current_count
));
emit
updateStatusString
(
QString
(
"sending waypoint ID %1 of %2 total"
).
arg
(
wp
->
seq
).
arg
(
current_count
));
qDebug
()
<<
"sent waypoint ("
<<
wp
->
seq
<<
") to ID "
<<
wp
->
target_system
<<
" WP Buffer count: "
<<
waypoint_buffer
.
count
();
mavlink_msg_waypoint_encode
(
uas
.
mavlink
->
getSystemId
(),
uas
.
mavlink
->
getComponentId
(),
&
message
,
wp
);
mavlink_msg_waypoint_encode
(
uas
.
mavlink
->
getSystemId
(),
uas
.
mavlink
->
getComponentId
(),
&
message
,
wp
);
uas
.
sendMessage
(
message
);
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint ("
<<
wp
->
seq
<<
") to ID "
<<
wp
->
target_system
;
}
}
}
}
...
...
src/ui/SlugsDataSensorView.cc
View file @
eff0195a
...
@@ -104,7 +104,7 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
...
@@ -104,7 +104,7 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
ui
->
m_GpsLongitude
->
setText
(
QString
::
number
(
lon
));
ui
->
m_GpsLongitude
->
setText
(
QString
::
number
(
lon
));
ui
->
m_GpsHeight
->
setText
(
QString
::
number
(
alt
));
ui
->
m_GpsHeight
->
setText
(
QString
::
number
(
alt
));
qDebug
()
<<
"GPS Position = "
<<
lat
<<
" - "
<<
lon
<<
" - "
<<
alt
;
//
qDebug()<<"GPS Position = "<<lat<<" - "<<lon<<" - "<<alt;
}
}
...
@@ -154,7 +154,7 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
...
@@ -154,7 +154,7 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
ui
->
m_Pitch
->
setPlainText
(
QString
::
number
(
slugpitch
));
ui
->
m_Pitch
->
setPlainText
(
QString
::
number
(
slugpitch
));
ui
->
m_Yaw
->
setPlainText
(
QString
::
number
(
slugyaw
));
ui
->
m_Yaw
->
setPlainText
(
QString
::
number
(
slugyaw
));
qDebug
()
<<
"Attitude change = "
<<
slugroll
<<
" - "
<<
slugpitch
<<
" - "
<<
slugyaw
;
//
qDebug()<<"Attitude change = "<<slugroll<<" - "<<slugpitch<<" - "<<slugyaw;
}
}
...
...
src/ui/SlugsDataSensorView.ui
View file @
eff0195a
...
@@ -7,7 +7,7 @@
...
@@ -7,7 +7,7 @@
<x>
0
</x>
<x>
0
</x>
<y>
0
</y>
<y>
0
</y>
<width>
399
</width>
<width>
399
</width>
<height>
604
</height>
<height>
598
</height>
</rect>
</rect>
</property>
</property>
<property
name=
"sizePolicy"
>
<property
name=
"sizePolicy"
>
...
@@ -31,18 +31,18 @@
...
@@ -31,18 +31,18 @@
<property
name=
"windowTitle"
>
<property
name=
"windowTitle"
>
<string>
Form
</string>
<string>
Form
</string>
</property>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout_2
3
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_2
5
"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QTabWidget"
name=
"SlugsSensorView_tabWidget"
>
<widget
class=
"QTabWidget"
name=
"SlugsSensorView_tabWidget"
>
<property
name=
"currentIndex"
>
<property
name=
"currentIndex"
>
<number>
1
</number>
<number>
0
</number>
</property>
</property>
<widget
class=
"QWidget"
name=
"tab"
>
<widget
class=
"QWidget"
name=
"tab"
>
<attribute
name=
"title"
>
<attribute
name=
"title"
>
<string>
Tab 1
</string>
<string>
Tab 1
</string>
</attribute>
</attribute>
<layout
class=
"Q
VBoxLayout"
name=
"verticalLayout_10
"
>
<layout
class=
"Q
GridLayout"
name=
"gridLayout_24
"
>
<item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_9"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_9"
>
<item>
<item>
<widget
class=
"QGroupBox"
name=
"position_groupBox"
>
<widget
class=
"QGroupBox"
name=
"position_groupBox"
>
...
@@ -2904,10 +2904,8 @@
...
@@ -2904,10 +2904,8 @@
<attribute
name=
"title"
>
<attribute
name=
"title"
>
<string>
Tab 3
</string>
<string>
Tab 3
</string>
</attribute>
</attribute>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_16"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_23"
>
<item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_4"
>
<item>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_2"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_2"
>
<property
name=
"minimumSize"
>
<property
name=
"minimumSize"
>
<size>
<size>
...
@@ -2924,8 +2922,8 @@
...
@@ -2924,8 +2922,8 @@
<property
name=
"title"
>
<property
name=
"title"
>
<string>
CPU Load
</string>
<string>
CPU Load
</string>
</property>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_12
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_20
"
>
<item
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_10"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_10"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_55"
>
<widget
class=
"QLabel"
name=
"label_55"
>
...
@@ -3109,7 +3107,7 @@
...
@@ -3109,7 +3107,7 @@
</layout>
</layout>
</widget>
</widget>
</item>
</item>
<item
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_3"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_3"
>
<property
name=
"minimumSize"
>
<property
name=
"minimumSize"
>
<size>
<size>
...
@@ -3126,8 +3124,8 @@
...
@@ -3126,8 +3124,8 @@
<property
name=
"title"
>
<property
name=
"title"
>
<string>
Air Data
</string>
<string>
Air Data
</string>
</property>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_13
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_21
"
>
<item
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_11"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_11"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_56"
>
<widget
class=
"QLabel"
name=
"label_56"
>
...
@@ -3311,9 +3309,7 @@
...
@@ -3311,9 +3309,7 @@
</layout>
</layout>
</widget>
</widget>
</item>
</item>
</layout>
<item
row=
"1"
column=
"0"
colspan=
"2"
>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_4"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_4"
>
<property
name=
"minimumSize"
>
<property
name=
"minimumSize"
>
<size>
<size>
...
@@ -3330,8 +3326,6 @@
...
@@ -3330,8 +3326,6 @@
<property
name=
"title"
>
<property
name=
"title"
>
<string>
Filtered Data
</string>
<string>
Filtered Data
</string>
</property>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_14"
>
<item>
<layout
class=
"QGridLayout"
name=
"gridLayout_15"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_15"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_12"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_12"
>
...
@@ -3520,7 +3514,7 @@
...
@@ -3520,7 +3514,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"0"
column=
"1"
rowspan=
"2
"
>
<item
row=
"0"
column=
"1
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_14"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_14"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_25"
>
<widget
class=
"QLabel"
name=
"label_25"
>
...
@@ -3701,7 +3695,7 @@
...
@@ -3701,7 +3695,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"1"
column=
"0"
rowspan=
"2
"
>
<item
row=
"1"
column=
"0
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_13"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_13"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_66"
>
<widget
class=
"QLabel"
name=
"label_66"
>
...
@@ -3882,7 +3876,7 @@
...
@@ -3882,7 +3876,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"2
"
column=
"1"
>
<item
row=
"1
"
column=
"1"
>
<spacer
name=
"verticalSpacer_3"
>
<spacer
name=
"verticalSpacer_3"
>
<property
name=
"orientation"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
<enum>
Qt::Vertical
</enum>
...
@@ -3890,17 +3884,15 @@
...
@@ -3890,17 +3884,15 @@
<property
name=
"sizeHint"
stdset=
"0"
>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<size>
<width>
20
</width>
<width>
20
</width>
<height>
40
</height>
<height>
84
</height>
</size>
</size>
</property>
</property>
</spacer>
</spacer>
</item>
</item>
</layout>
</layout>
</item>
</layout>
</widget>
</widget>
</item>
</item>
<item>
<item
row=
"2"
column=
"0"
colspan=
"2"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_5"
>
<widget
class=
"QGroupBox"
name=
"sensorBiases_groupBox_5"
>
<property
name=
"minimumSize"
>
<property
name=
"minimumSize"
>
<size>
<size>
...
@@ -3917,8 +3909,6 @@
...
@@ -3917,8 +3909,6 @@
<property
name=
"title"
>
<property
name=
"title"
>
<string>
Raw Data
</string>
<string>
Raw Data
</string>
</property>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_15"
>
<item>
<layout
class=
"QGridLayout"
name=
"gridLayout_16"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_16"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_17"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_17"
>
...
@@ -4101,7 +4091,7 @@
...
@@ -4101,7 +4091,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"0"
column=
"1"
rowspan=
"2
"
>
<item
row=
"0"
column=
"1
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_18"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_18"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_71"
>
<widget
class=
"QLabel"
name=
"label_71"
>
...
@@ -4282,7 +4272,7 @@
...
@@ -4282,7 +4272,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"1"
column=
"0"
rowspan=
"2
"
>
<item
row=
"1"
column=
"0
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_19"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_19"
>
<item
row=
"0"
column=
"0"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_74"
>
<widget
class=
"QLabel"
name=
"label_74"
>
...
@@ -4463,7 +4453,7 @@
...
@@ -4463,7 +4453,7 @@
</item>
</item>
</layout>
</layout>
</item>
</item>
<item
row=
"2
"
column=
"1"
>
<item
row=
"1
"
column=
"1"
>
<spacer
name=
"verticalSpacer_4"
>
<spacer
name=
"verticalSpacer_4"
>
<property
name=
"orientation"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
<enum>
Qt::Vertical
</enum>
...
@@ -4471,14 +4461,12 @@
...
@@ -4471,14 +4461,12 @@
<property
name=
"sizeHint"
stdset=
"0"
>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<size>
<width>
20
</width>
<width>
20
</width>
<height>
40
</height>
<height>
84
</height>
</size>
</size>
</property>
</property>
</spacer>
</spacer>
</item>
</item>
</layout>
</layout>
</item>
</layout>
</widget>
</widget>
</item>
</item>
</layout>
</layout>
...
...
src/ui/SlugsPadCameraControl.cpp
View file @
eff0195a
...
@@ -27,15 +27,12 @@ SlugsPadCameraControl::~SlugsPadCameraControl()
...
@@ -27,15 +27,12 @@ SlugsPadCameraControl::~SlugsPadCameraControl()
void
SlugsPadCameraControl
::
mouseMoveEvent
(
QMouseEvent
*
event
)
void
SlugsPadCameraControl
::
mouseMoveEvent
(
QMouseEvent
*
event
)
{
{
//emit mouseMoveCoord(event->x(),event->y());
//emit mouseMoveCoord(event->x(),event->y());
if
(
dragging
)
if
(
dragging
)
{
if
(
abs
(
x1
-
event
->
x
())
>
20
||
abs
(
y1
-
event
->
y
())
>
20
)
{
{
getDeltaPositionPad
(
event
->
x
(),
event
->
y
());
// getDeltaPositionPad(event->x(), event->y());
x1
=
event
->
x
();
y1
=
event
->
y
();
}
}
}
...
@@ -54,7 +51,7 @@ void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event)
...
@@ -54,7 +51,7 @@ void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event)
{
{
dragging
=
false
;
dragging
=
false
;
//emit mouseReleaseCoord(event->x(),event->y());
//emit mouseReleaseCoord(event->x(),event->y());
//
getDeltaPositionPad(event->x(), event->y());
getDeltaPositionPad
(
event
->
x
(),
event
->
y
());
xFin
=
event
->
x
();
xFin
=
event
->
x
();
yFin
=
event
->
y
();
yFin
=
event
->
y
();
...
@@ -105,6 +102,10 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
...
@@ -105,6 +102,10 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
double
bearing
=
localMeasures
.
x
();
double
bearing
=
localMeasures
.
x
();
double
dist
=
getDistPixel
(
y1
,
x1
,
y2
,
x2
);
double
dist
=
getDistPixel
(
y1
,
x1
,
y2
,
x2
);
// this only convert real bearing to frame widget bearing
bearing
=
bearing
+
90
;
if
(
bearing
>=
360
)
bearing
=
bearing
-
360
;
if
(((
bearing
>
330
)
&&
(
bearing
<
360
))
||
((
bearing
>=
0
)
&&
(
bearing
<=
30
)))
if
(((
bearing
>
330
)
&&
(
bearing
<
360
))
||
((
bearing
>=
0
)
&&
(
bearing
<=
30
)))
...
@@ -210,16 +211,9 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
...
@@ -210,16 +211,9 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
// distancia = (float) hipotenusa;
// distancia = (float) hipotenusa;
}
}
/**
* Esta funcin xxxxxxxxx
QPointF
SlugsPadCameraControl
::
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
* @param double lat1 -->
double
lon2
,
double
lat2
)
* @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
;
double
cateto_opuesto
,
cateto_adyacente
,
hipotenusa
,
distancia
,
marcacion
;
...
@@ -256,9 +250,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
...
@@ -256,9 +250,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
else
if
((
lat1
==
lat2
)
&&
(
lon1
==
lon2
))
//0
else
if
((
lat1
==
lat2
)
&&
(
lon1
==
lon2
))
//0
marcacion
=
0.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
);
return
QPointF
(
marcacion
,
distancia
);
...
...
src/ui/SlugsPadCameraControl.h
View file @
eff0195a
...
@@ -19,12 +19,16 @@ public:
...
@@ -19,12 +19,16 @@ public:
public
slots
:
public
slots
:
void
getDeltaPositionPad
(
int
x
,
int
y
);
void
getDeltaPositionPad
(
int
x
,
int
y
);
double
getDistPixel
(
int
x1
,
int
y1
,
int
x2
,
int
y2
);
double
getDistPixel
(
int
x1
,
int
y1
,
int
x2
,
int
y2
);
QPointF
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
);
QPointF
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
);
QPointF
getPointBy_BearingDistance
(
double
lat1
,
double
lon1
,
double
rumbo
,
double
distancia
);
QPointF
getPointBy_BearingDistance
(
double
lat1
,
double
lon1
,
double
rumbo
,
double
distancia
);
signals:
signals:
void
mouseMoveCoord
(
int
x
,
int
y
);
void
mouseMoveCoord
(
int
x
,
int
y
);
void
mousePressCoord
(
int
x
,
int
y
);
void
mousePressCoord
(
int
x
,
int
y
);
...
...
src/ui/SlugsVideoCamControl.ui
View file @
eff0195a
...
@@ -22,10 +22,10 @@
...
@@ -22,10 +22,10 @@
<property
name=
"windowTitle"
>
<property
name=
"windowTitle"
>
<string>
Form
</string>
<string>
Form
</string>
</property>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<item>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_x"
>
<widget
class=
"QLabel"
name=
"label_x"
>
<property
name=
"mouseTracking"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -35,7 +35,7 @@
...
@@ -35,7 +35,7 @@
</property>
</property>
</widget>
</widget>
</item>
</item>
<item>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLabel"
name=
"label_y"
>
<widget
class=
"QLabel"
name=
"label_y"
>
<property
name=
"mouseTracking"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
<bool>
true
</bool>
...
@@ -45,21 +45,17 @@
...
@@ -45,21 +45,17 @@
</property>
</property>
</widget>
</widget>
</item>
</item>
<item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"Q
Label"
name=
"label_dir
"
>
<widget
class=
"Q
CheckBox"
name=
"viewCamBordeatMap_checkBox
"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
Camera
Pos
</string>
<string>
Camera
at Map
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
</layout>
</item>
<item
row=
"1"
column=
"0"
>
<item
row=
"1"
column=
"0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<widget
class=
"QLabel"
name=
"label_dir"
>
<item>
<widget
class=
"QCheckBox"
name=
"viewCamBordeatMap_checkBox"
>
<property
name=
"text"
>
<property
name=
"text"
>
<string>
Camera
at Map
</string>
<string>
Camera
Pos
</string>
</property>
</property>
</widget>
</widget>
</item>
</item>
...
...
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