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
01fd0113
Commit
01fd0113
authored
Sep 29, 2014
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fix Windows 64 bit warnings
parent
61dd5731
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
15 additions
and
14 deletions
+15
-14
MAVLinkSimulationWaypointPlanner.cc
src/comm/MAVLinkSimulationWaypointPlanner.cc
+2
-2
MockMavlinkFileServer.cc
src/qgcunittest/MockMavlinkFileServer.cc
+2
-2
QGCUASFileManager.cc
src/uas/QGCUASFileManager.cc
+3
-2
UAS.cc
src/uas/UAS.cc
+1
-1
QGCMAVLinkInspector.cc
src/ui/QGCMAVLinkInspector.cc
+1
-1
FlightModeConfig.cc
src/ui/configuration/FlightModeConfig.cc
+4
-4
FlightModeConfig.h
src/ui/configuration/FlightModeConfig.h
+2
-2
No files found.
src/comm/MAVLinkSimulationWaypointPlanner.cc
View file @
01fd0113
...
...
@@ -890,7 +890,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
}
else
{
if
(
verbose
)
qDebug
(
"Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST from %u but have no waypoints, staying in
\n
"
,
msg
->
sysid
);
}
protocol_current_count
=
waypoints
->
size
(
);
protocol_current_count
=
static_cast
<
uint16_t
>
(
waypoints
->
size
()
);
send_waypoint_count
(
msg
->
sysid
,
msg
->
compid
,
protocol_current_count
);
}
else
{
if
(
verbose
)
qDebug
(
"Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST_LIST because i'm doing something else already (state=%i).
\n
"
,
current_state
);
...
...
@@ -999,7 +999,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
send_waypoint_ack
(
protocol_current_partner_systemid
,
protocol_current_partner_compid
,
0
);
if
(
current_active_wp_id
>
waypoints_receive_buffer
->
size
()
-
1
)
{
current_active_wp_id
=
waypoints_receive_buffer
->
size
(
)
-
1
;
current_active_wp_id
=
static_cast
<
uint16_t
>
(
waypoints_receive_buffer
->
size
()
)
-
1
;
}
// switch the waypoints list
...
...
src/qgcunittest/MockMavlinkFileServer.cc
View file @
01fd0113
...
...
@@ -86,8 +86,8 @@ void MockMavlinkFileServer::_listCommand(QGCUASFileManager::Request* request, ui
char
*
bufPtr
=
(
char
*
)
&
ackResponse
.
data
[
0
];
for
(
int
i
=
0
;
i
<
_fileList
.
size
();
i
++
)
{
strcpy
(
bufPtr
,
_fileList
[
i
].
toStdString
().
c_str
());
size_t
cchFilename
=
strlen
(
bufPtr
);
Q_ASSERT
(
cchFilename
);
uint8_t
cchFilename
=
static_cast
<
uint8_t
>
(
strlen
(
bufPtr
)
);
Q_ASSERT
(
cchFilename
);
ackResponse
.
hdr
.
size
+=
cchFilename
+
1
;
bufPtr
+=
cchFilename
+
1
;
}
...
...
src/uas/QGCUASFileManager.cc
View file @
01fd0113
...
...
@@ -159,8 +159,9 @@ void QGCUASFileManager::_listAckResponse(Request* listAck)
// get the length of the name
uint8_t
cBytesLeft
=
cBytes
-
offset
;
size_t
nlen
=
strnlen
(
ptr
,
cBytesLeft
);
uint8_t
nlen
=
static_cast
<
uint8_t
>
(
strnlen
(
ptr
,
cBytesLeft
)
);
if
((
*
ptr
==
'S'
&&
nlen
>
1
)
||
(
*
ptr
!=
'S'
&&
nlen
<
2
))
{
if
(
nlen
<
2
)
{
_currentOperation
=
kCOIdle
;
_emitErrorMessage
(
tr
(
"Incorrectly formed list entry: '%1'"
).
arg
(
ptr
));
return
;
...
...
@@ -315,7 +316,7 @@ void QGCUASFileManager::listDirectory(const QString& dirPath)
void
QGCUASFileManager
::
_fillRequestWithString
(
Request
*
request
,
const
QString
&
str
)
{
strncpy
((
char
*
)
&
request
->
data
[
0
],
str
.
toStdString
().
c_str
(),
sizeof
(
request
->
data
));
request
->
hdr
.
size
=
st
rnlen
((
const
char
*
)
&
request
->
data
[
0
],
sizeof
(
request
->
data
));
request
->
hdr
.
size
=
st
atic_cast
<
uint8_t
>
(
strnlen
((
const
char
*
)
&
request
->
data
[
0
],
sizeof
(
request
->
data
)
));
}
void
QGCUASFileManager
::
_sendListCommand
(
void
)
...
...
src/uas/UAS.cc
View file @
01fd0113
...
...
@@ -1953,7 +1953,7 @@ QImage UAS::getImage()
QString
header
(
"P5
\n
%1 %2
\n
%3
\n
"
);
header
=
header
.
arg
(
imageWidth
).
arg
(
imageHeight
).
arg
(
imgColors
);
QByteArray
tmpImage
(
header
.
toStdString
().
c_str
(),
header
.
toStdString
().
size
());
QByteArray
tmpImage
(
header
.
toStdString
().
c_str
(),
header
.
length
());
tmpImage
.
append
(
imageRecBuffer
);
//qDebug() << "IMAGE SIZE:" << tmpImage.size() << "HEADER SIZE: (15):" << header.size() << "HEADER: " << header;
...
...
src/ui/QGCMAVLinkInspector.cc
View file @
01fd0113
...
...
@@ -293,7 +293,7 @@ void QGCMAVLinkInspector::refreshView()
{
const
char
*
msgname
=
messageInfo
[
i
].
name
;
in
t
namelen
=
strnlen
(
msgname
,
5
);
size_
t
namelen
=
strnlen
(
msgname
,
5
);
if
(
namelen
<
3
)
{
continue
;
...
...
src/ui/configuration/FlightModeConfig.cc
View file @
01fd0113
...
...
@@ -181,9 +181,9 @@ void FlightModeConfig::activeUASSet(UASInterface *uas)
}
// Set up the combo boxes
for
(
size_
t
i
=
0
;
i
<
_cModes
;
i
++
)
{
for
(
in
t
i
=
0
;
i
<
_cModes
;
i
++
)
{
// Fill each combo box with the available flight modes
for
(
size_
t
j
=
0
;
j
<
_cModeInfo
;
j
++
)
{
for
(
in
t
j
=
0
;
j
<
_cModeInfo
;
j
++
)
{
_rgCombo
[
i
]
->
addItem
(
_rgModeInfo
[
j
].
label
,
QVariant
(
QChar
((
char
)
_rgModeInfo
[
j
].
value
)));
}
...
...
@@ -260,13 +260,13 @@ void FlightModeConfig::parameterChanged(int uas, int component, QString paramete
}
}
else
{
// Loop over the flight mode params looking for a match
for
(
size_
t
i
=
0
;
i
<
_cModes
;
i
++
)
{
for
(
in
t
i
=
0
;
i
<
_cModes
;
i
++
)
{
if
(
parameterName
==
_rgModeParam
[
i
])
{
// We found a match, i is now the index of the combo box which displays that mode slot
// Loop over the mode info till we find the matching value, this tells us which row in the
// combo box to select.
QComboBox
*
combo
=
_rgCombo
[
i
];
for
(
size_
t
j
=
0
;
j
<
_cModeInfo
;
j
++
)
{
for
(
in
t
j
=
0
;
j
<
_cModeInfo
;
j
++
)
{
if
(
_rgModeInfo
[
j
].
value
==
iValue
)
{
combo
->
setCurrentIndex
(
j
);
return
;
...
...
src/ui/configuration/FlightModeConfig.h
View file @
01fd0113
...
...
@@ -58,9 +58,9 @@ private:
static
const
FlightModeInfo_t
_rgModeInfoRotor
[];
static
const
FlightModeInfo_t
_rgModeInfoRover
[];
const
FlightModeInfo_t
*
_rgModeInfo
;
size_t
_cModeInfo
;
int
_cModeInfo
;
static
const
size_
t
_cModes
=
6
;
static
const
in
t
_cModes
=
6
;
static
const
char
*
_rgModeParamFixedWing
[
_cModes
];
static
const
char
*
_rgModeParamRotor
[
_cModes
];
...
...
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