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
ee9cbf32
Commit
ee9cbf32
authored
Dec 03, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Working on having Slugs comply with the WP protocol
parent
d4303c21
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
6 additions
and
68 deletions
+6
-68
SerialLink.cc
src/comm/SerialLink.cc
+2
-2
SlugsMAV.cc
src/uas/SlugsMAV.cc
+1
-65
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+0
-1
WaypointList.cc
src/ui/WaypointList.cc
+1
-0
Linecharts.cc
src/ui/linechart/Linecharts.cc
+2
-0
No files found.
src/comm/SerialLink.cc
View file @
ee9cbf32
...
...
@@ -89,8 +89,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
}
#else
// *nix (Linux, MacOS tested) serial port support
//
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
port
=
new
QextSerialPort
(
porthandle
,
QextSerialPort
::
EventDriven
);
port
=
new
QextSerialPort
(
porthandle
,
QextSerialPort
::
Polling
);
//
port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
port
->
setTimeout
(
timeout
);
// Timeout of 0 ms, we don't want to wait for data, we just poll again next time
port
->
setBaudRate
(
baudrate
);
port
->
setFlowControl
(
flow
);
...
...
src/uas/SlugsMAV.cc
View file @
ee9cbf32
...
...
@@ -59,77 +59,13 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
void
SlugsMAV
::
receiveMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
)
{
// Let UAS handle the default message set
//
UAS::receiveMessage(link, message);
UAS
::
receiveMessage
(
link
,
message
);
// Handle your special messages mavlink_message_t* msg = &message;
switch
(
message
.
msgid
)
{
case
MAVLINK_MSG_ID_HEARTBEAT
:
emit
heartbeat
(
this
);
// Set new type if it has changed
if
(
this
->
type
!=
mavlink_msg_heartbeat_get_type
(
&
message
))
{
this
->
type
=
mavlink_msg_heartbeat_get_type
(
&
message
);
emit
systemTypeSet
(
this
,
type
);
}
break
;
case
MAVLINK_MSG_ID_RAW_IMU
:
mavlink_msg_raw_imu_decode
(
&
message
,
&
mlRawImuData
);
break
;
case
MAVLINK_MSG_ID_WAYPOINT_COUNT
:
mavlink_waypoint_count_t
wpct
;
mavlink_msg_waypoint_count_decode
(
&
message
,
&
wpct
);
if
(
wpct
.
target_system
==
mavlink
->
getSystemId
()
&&
wpct
.
target_component
==
mavlink
->
getComponentId
())
{
waypointManager
.
handleWaypointCount
(
message
.
sysid
,
message
.
compid
,
wpct
.
count
);
}
break
;
case
MAVLINK_MSG_ID_WAYPOINT
:
mavlink_waypoint_t
wp
;
mavlink_msg_waypoint_decode
(
&
message
,
&
wp
);
//qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
if
(
wp
.
target_system
==
mavlink
->
getSystemId
()
&&
wp
.
target_component
==
mavlink
->
getComponentId
())
{
waypointManager
.
handleWaypoint
(
message
.
sysid
,
message
.
compid
,
&
wp
);
}
break
;
case
MAVLINK_MSG_ID_WAYPOINT_ACK
:
mavlink_waypoint_ack_t
wpa
;
mavlink_msg_waypoint_ack_decode
(
&
message
,
&
wpa
);
if
(
wpa
.
target_system
==
mavlink
->
getSystemId
()
&&
wpa
.
target_component
==
mavlink
->
getComponentId
())
{
waypointManager
.
handleWaypointAck
(
message
.
sysid
,
message
.
compid
,
&
wpa
);
}
break
;
case
MAVLINK_MSG_ID_WAYPOINT_REQUEST
:
mavlink_waypoint_request_t
wpr
;
mavlink_msg_waypoint_request_decode
(
&
message
,
&
wpr
);
qDebug
()
<<
"Waypoint Request"
<<
wpr
.
seq
;
if
(
wpr
.
target_system
==
mavlink
->
getSystemId
()
&&
wpr
.
target_component
==
mavlink
->
getComponentId
())
{
waypointManager
.
handleWaypointRequest
(
message
.
sysid
,
message
.
compid
,
&
wpr
);
}
break
;
case
MAVLINK_MSG_ID_WAYPOINT_REACHED
:
mavlink_waypoint_reached_t
wpre
;
mavlink_msg_waypoint_reached_decode
(
&
message
,
&
wpre
);
waypointManager
.
handleWaypointReached
(
message
.
sysid
,
message
.
compid
,
&
wpre
);
break
;
case
MAVLINK_MSG_ID_WAYPOINT_CURRENT
:
mavlink_waypoint_current_t
wpc
;
mavlink_msg_waypoint_current_decode
(
&
message
,
&
wpc
);
waypointManager
.
handleWaypointCurrent
(
message
.
sysid
,
message
.
compid
,
&
wpc
);
break
;
#ifdef MAVLINK_ENABLED_SLUGS
case
MAVLINK_MSG_ID_BOOT
:
...
...
src/uas/UASWaypointManager.cc
View file @
ee9cbf32
...
...
@@ -440,7 +440,6 @@ void UASWaypointManager::readWaypoints()
void
UASWaypointManager
::
writeWaypoints
()
{
qDebug
()
<<
"+++++++++++++++++++>>>> Entro Funcion Write WP"
;
if
(
current_state
==
WP_IDLE
)
{
if
(
waypoints
.
count
()
>
0
)
...
...
src/ui/WaypointList.cc
View file @
ee9cbf32
...
...
@@ -490,6 +490,7 @@ void WaypointList::on_clearWPListButton_clicked()
widget
->
remove
();
}
uas
->
getWaypointManager
().
clearWaypointList
();
isGlobalWP
=
false
;
...
...
src/ui/linechart/Linecharts.cc
View file @
ee9cbf32
...
...
@@ -54,7 +54,9 @@ void Linecharts::addSystem(UASInterface* uas)
LinechartWidget
*
widget
=
new
LinechartWidget
(
uas
->
getUASID
(),
this
);
addWidget
(
widget
);
plots
.
insert
(
uas
->
getUASID
(),
widget
);
#ifndef MAVLINK_ENABLED_SLUGS
connect
(
uas
,
SIGNAL
(
valueChanged
(
int
,
QString
,
double
,
quint64
)),
widget
,
SLOT
(
appendData
(
int
,
QString
,
double
,
quint64
)));
#endif
connect
(
widget
,
SIGNAL
(
logfileWritten
(
QString
)),
this
,
SIGNAL
(
logfileWritten
(
QString
)));
// Set system active if this is the only system
if
(
active
)
...
...
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