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
51069e06
Commit
51069e06
authored
Jun 10, 2011
by
LM
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor compile fixes for v1.0
parent
7948025a
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
17 additions
and
17 deletions
+17
-17
qgroundcontrol.pri
qgroundcontrol.pri
+2
-2
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+4
-4
Pixhawk3DWidget.cc
src/ui/map3D/Pixhawk3DWidget.cc
+9
-9
WaypointGroupNode.cc
src/ui/map3D/WaypointGroupNode.cc
+2
-2
No files found.
qgroundcontrol.pri
View file @
51069e06
...
...
@@ -221,7 +221,7 @@ message("Compiling for linux 32")
DEFINES += QGC_LIBFREENECT_ENABLED
}
QMAKE_POST_LINK += && cp -rf $$BASEDIR/
model
s $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/
file
s $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
...
...
@@ -295,7 +295,7 @@ linux-g++-64 {
DEFINES += QGC_LIBFREENECT_ENABLED
}
QMAKE_POST_LINK += && cp -rf $$BASEDIR/
model
s $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/
file
s $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
51069e06
...
...
@@ -757,7 +757,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for
(
i
=
onboardParams
.
begin
();
i
!=
onboardParams
.
end
();
++
i
)
{
if
(
j
!=
5
)
{
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
0
,
onboardParams
.
size
(),
j
);
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
j
);
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
...
...
@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams
.
insert
(
key
,
set
.
param_value
);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
set
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
set
.
param_value
,
0
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
set
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
set
.
param_value
,
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
...
...
@@ -806,7 +806,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float
paramValue
=
onboardParams
.
value
(
key
);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
0
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
...
...
@@ -818,7 +818,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float
paramValue
=
onboardParams
.
value
(
key
);
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
0
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
...
...
src/ui/map3D/Pixhawk3DWidget.cc
View file @
51069e06
...
...
@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text)
if
(
text
.
compare
(
"Global"
)
==
0
)
{
frame
=
MAV_FRAME_GLOBAL
;
}
else
if
(
text
.
compare
(
"Local"
)
==
0
)
{
frame
=
MAV_FRAME_LOCAL
;
frame
=
MAV_FRAME_LOCAL
_NED
;
}
getPosition
(
lastRobotX
,
lastRobotY
,
lastRobotZ
);
...
...
@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void)
getGlobalCursorPosition
(
getMouseX
(),
getMouseY
(),
altitude
);
target
.
set
(
cursorWorldCoords
.
first
,
cursorWorldCoords
.
second
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
double
z
=
uas
->
getLocalZ
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
...
...
@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void)
latitude
,
longitude
);
wp
=
new
Waypoint
(
0
,
longitude
,
latitude
,
altitude
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
double
z
=
uas
->
getLocalZ
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
...
...
@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void)
waypoint
->
setX
(
longitude
);
waypoint
->
setY
(
latitude
);
waypoint
->
setZ
(
altitude
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
double
z
=
uas
->
getLocalZ
();
std
::
pair
<
double
,
double
>
cursorWorldCoords
=
...
...
@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
Waypoint
*
waypoint
=
waypoints
.
at
(
selectedWpIndex
);
double
altitude
=
waypoint
->
getZ
();
if
(
frame
==
MAV_FRAME_LOCAL
)
{
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
altitude
=
-
altitude
;
}
...
...
@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
if
(
ok
)
{
if
(
frame
==
MAV_FRAME_GLOBAL
)
{
waypoint
->
setZ
(
newAltitude
);
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
waypoint
->
setZ
(
-
newAltitude
);
}
}
...
...
@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z,
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
x
,
y
,
utmZone
);
z
=
-
altitude
;
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
x
=
uas
->
getLocalX
();
y
=
uas
->
getLocalY
();
z
=
uas
->
getLocalZ
();
...
...
@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z,
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
x
,
y
,
utmZone
);
z
=
-
altitude
;
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
x
=
uas
->
getLocalX
();
y
=
uas
->
getLocalY
();
z
=
uas
->
getLocalZ
();
...
...
@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
oss
.
precision
(
6
);
oss
<<
" Cursor ["
<<
cursorLatitude
<<
" "
<<
cursorLongitude
<<
"]"
;
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
oss
<<
" x = "
<<
robotX
<<
" y = "
<<
robotY
<<
" z = "
<<
robotZ
<<
...
...
src/ui/map3D/WaypointGroupNode.cc
View file @
51069e06
...
...
@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
QString
utmZone
;
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
robotX
,
robotY
,
utmZone
);
robotZ
=
-
altitude
;
}
else
if
(
frame
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
frame
==
MAV_FRAME_LOCAL
_NED
)
{
robotX
=
uas
->
getLocalX
();
robotY
=
uas
->
getLocalY
();
robotZ
=
uas
->
getLocalZ
();
...
...
@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z)
QString
utmZone
;
Imagery
::
LLtoUTM
(
latitude
,
longitude
,
x
,
y
,
utmZone
);
z
=
-
altitude
;
}
else
if
(
wp
->
getFrame
()
==
MAV_FRAME_LOCAL
)
{
}
else
if
(
wp
->
getFrame
()
==
MAV_FRAME_LOCAL
_NED
)
{
x
=
wp
->
getX
();
y
=
wp
->
getY
();
z
=
wp
->
getZ
();
...
...
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