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
16a68ab5
Commit
16a68ab5
authored
Jan 01, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed a whole bunch of compile warnings
parent
74c36838
Changes
12
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
296 additions
and
283 deletions
+296
-283
layer.cpp
lib/QMapControl/src/layer.cpp
+4
-3
Core.cc
src/Core.cc
+1
-0
MAVLinkXMLParser.cc
src/comm/MAVLinkXMLParser.cc
+2
-2
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+4
-1
MapWidget.cc
src/ui/MapWidget.cc
+269
-268
SlugsPIDControl.cpp
src/ui/SlugsPIDControl.cpp
+2
-0
SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp
+3
-2
Imagery.cc
src/ui/map3D/Imagery.cc
+2
-2
Pixhawk3DWidget.cc
src/ui/map3D/Pixhawk3DWidget.cc
+1
-1
PixhawkCheetahGeode.cc
src/ui/map3D/PixhawkCheetahGeode.cc
+4
-3
WaypointGroupNode.cc
src/ui/map3D/WaypointGroupNode.cc
+3
-1
UASView.cc
src/ui/uas/UASView.cc
+1
-0
No files found.
lib/QMapControl/src/layer.cpp
View file @
16a68ab5
...
...
@@ -99,9 +99,10 @@ namespace qmapcontrol
Geometry
*
Layer
::
get_Geometry
(
int
index
)
{
Geometry
*
geo
=
NULL
;
if
(
geometrySelected
)
{
return
geometrySelected
;
geo
=
geometrySelected
;
}
else
{
...
...
@@ -110,7 +111,7 @@ namespace qmapcontrol
Geometry
*
geometry
=
geometries
[
i
];
if
(
geometry
->
name
()
==
QString
::
number
(
index
))
{
return
geometry
;
geo
=
geometry
;
}
}
...
...
@@ -124,7 +125,7 @@ namespace qmapcontrol
// }
}
return
geo
;
}
bool
Layer
::
isVisible
()
const
...
...
src/Core.cc
View file @
16a68ab5
...
...
@@ -122,6 +122,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink
*
simulationLink
=
new
MAVLinkSimulationLink
(
":/demo-log.txt"
);
simulationLink
->
disconnect
();
//mainWindow->addLink(simulationLink);
mainWindow
=
MainWindow
::
instance
();
...
...
src/comm/MAVLinkXMLParser.cc
View file @
16a68ab5
...
...
@@ -496,7 +496,7 @@ bool MAVLinkXMLParser::generate()
if
(
fieldType
==
"uint8_t_mavlink_version"
)
{
unpackingCode
=
QString
(
"
\t
return
%1;"
).
arg
(
mavlinkVersion
);
unpackingCode
=
QString
(
"
\t
return
(%1)(msg->payload%2)[0];"
).
arg
(
"uint8_t"
,
prepends
);
}
else
if
(
fieldType
==
"uint8_t"
||
fieldType
==
"int8_t"
)
{
...
...
@@ -531,7 +531,7 @@ bool MAVLinkXMLParser::generate()
// Generate the message decoding function
if
(
fieldType
.
contains
(
"uint8_t_mavlink_version"
))
{
unpacking
+=
unpackingComment
+
QString
(
"static inline
uint8_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg)
\n
{
\n\t
return %3;
\n
}
\n\n
"
).
arg
(
messageName
,
fieldName
).
arg
(
mavlinkVersion
);
unpacking
+=
unpackingComment
+
QString
(
"static inline
%1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)
\n
{
\n
%4
\n
}
\n\n
"
).
arg
(
"uint8_t"
,
messageName
,
fieldName
,
unpackingCode
);
decodeLines
+=
""
;
prepends
+=
"+sizeof(uint8_t)"
;
}
...
...
src/uas/UASWaypointManager.cc
View file @
16a68ab5
...
...
@@ -394,11 +394,14 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
void
UASWaypointManager
::
globalAddWaypoint
(
Waypoint
*
wp
)
{
// FIXME Will be removed
Q_UNUSED
(
wp
);
}
int
UASWaypointManager
::
globalRemoveWaypoint
(
quint16
seq
)
{
// FIXME Will be removed
Q_UNUSED
(
seq
);
return
0
;
}
...
...
src/ui/MapWidget.cc
View file @
16a68ab5
This diff is collapsed.
Click to expand it.
src/ui/SlugsPIDControl.cpp
View file @
16a68ab5
...
...
@@ -640,6 +640,8 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
#else
Q_UNUSED
(
PIDtype
);
#endif // MAVLINK_ENABLED_SLUG
}
...
...
src/ui/SlugsPadCameraControl.cpp
View file @
16a68ab5
...
...
@@ -221,7 +221,8 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
*/
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
;
double
marcacion
=
0.0
;
//latitude and longitude first point
...
...
@@ -234,7 +235,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
cateto_adyacente
=
abs
((
lon1
-
lon2
));
hipotenusa
=
sqrt
(
pow
(
cateto_opuesto
,
2
)
+
pow
(
cateto_adyacente
,
2
));
distancia
=
hipotenusa
*
60
;
distancia
=
hipotenusa
*
60
.0
;
if
((
lat1
<
lat2
)
&&
(
lon1
>
lon2
))
//primer cuadrante
...
...
src/ui/map3D/Imagery.cc
View file @
16a68ab5
...
...
@@ -75,7 +75,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
return
;
}
double
tileResolution
;
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
...
...
@@ -131,7 +131,7 @@ Imagery::draw2D(double windowWidth, double windowHeight,
return
;
}
double
tileResolution
;
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
...
...
src/ui/map3D/Pixhawk3DWidget.cc
View file @
16a68ab5
...
...
@@ -241,7 +241,7 @@ Pixhawk3DWidget::insertWaypoint(void)
{
if
(
uas
)
{
Waypoint
*
wp
;
Waypoint
*
wp
=
NULL
;
if
(
frame
==
MAV_FRAME_GLOBAL
)
{
double
latitude
=
uas
->
getLatitude
();
...
...
src/ui/map3D/PixhawkCheetahGeode.cc
View file @
16a68ab5
...
...
@@ -59300,9 +59300,10 @@ static GLfloat normals [22155][3] = {
GLfloat textures[1][2]={{0.0f,0.0f}};
/*Material indicies*/
/*{material index,face count}*/
static int material_ref [1][2] = {
{0,77848}
};
//static int material_ref [1][2] = {
//{0,77848}
//};
void MyMaterial(GLenum mode, GLfloat * f, GLfloat alpha)
{
GLfloat d[4];
src/ui/map3D/WaypointGroupNode.cc
View file @
16a68ab5
...
...
@@ -53,7 +53,9 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
{
if
(
uas
)
{
double
robotX
,
robotY
,
robotZ
;
double
robotX
=
0.0
;
double
robotY
=
0.0
;
double
robotZ
=
0.0
;
if
(
frame
==
MAV_FRAME_GLOBAL
)
{
double
latitude
=
uas
->
getLatitude
();
...
...
src/ui/uas/UASView.cc
View file @
16a68ab5
...
...
@@ -215,6 +215,7 @@ void UASView::hideEvent(QHideEvent* event)
void
UASView
::
receiveHeartbeat
(
UASInterface
*
uas
)
{
Q_UNUSED
(
uas
);
QString
colorstyle
;
heartbeatColor
=
QColor
(
20
,
200
,
20
);
colorstyle
=
colorstyle
.
sprintf
(
"QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}"
,
...
...
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