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
e6ed6da3
Commit
e6ed6da3
authored
Feb 10, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Last adjustments to new mission structure
parent
522297a4
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
35 additions
and
38 deletions
+35
-38
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+1
-1
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+1
-1
UAS.cc
src/uas/UAS.cc
+2
-2
WaypointView.cc
src/ui/WaypointView.cc
+31
-34
No files found.
src/comm/MAVLinkProtocol.cc
View file @
e6ed6da3
...
...
@@ -180,7 +180,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Write message to buffer
mavlink_msg_to_send_buffer
(
buf
+
sizeof
(
quint64
),
&
message
);
QByteArray
b
((
const
char
*
)
buf
,
len
);
if
(
m_logfile
->
write
(
b
)
<
static_cast
<
int
>
(
MAVLINK_MAX_PACKET_LEN
+
sizeof
(
quint64
)))
if
(
m_logfile
->
write
(
b
)
<
static_cast
<
qint64
>
(
MAVLINK_MAX_PACKET_LEN
+
sizeof
(
quint64
)))
{
emit
protocolStatusMessage
(
tr
(
"MAVLink Logging failed"
),
tr
(
"Could not write to file %1, disabling logging."
).
arg
(
m_logfile
->
fileName
()));
// Stop logging
...
...
src/comm/MAVLinkSimulationMAV.cc
View file @
e6ed6da3
...
...
@@ -168,7 +168,7 @@ void MAVLinkSimulationMAV::mainloop()
hud
.
airspeed
=
pos
.
vx
;
hud
.
groundspeed
=
pos
.
vx
;
hud
.
alt
=
pos
.
alt
;
hud
.
heading
=
((
yaw
/
M_PI
)
*
180.0
f
+
180.0
f
)
;
hud
.
heading
=
static_cast
<
int
>
((
yaw
/
M_PI
)
*
180.0
f
+
180.0
f
)
%
360
;
hud
.
climb
=
pos
.
vz
;
hud
.
throttle
=
90
;
mavlink_msg_vfr_hud_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
msg
,
&
hud
);
...
...
src/uas/UAS.cc
View file @
e6ed6da3
...
...
@@ -441,8 +441,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"throttle"
,
"m/s"
,
hud
.
throttle
,
time
);
emit
thrustChanged
(
this
,
hud
.
throttle
/
100.0
);
emit
altitudeChanged
(
uasId
,
hud
.
alt
);
yaw
=
(
hud
.
heading
-
180.0
f
/
360.0
f
)
*
M_PI
;
emit
attitudeChanged
(
this
,
roll
,
pitch
,
yaw
,
getUnixTime
());
//
yaw = (hud.heading-180.0f/360.0f)*M_PI;
//
emit attitudeChanged(this, roll, pitch, yaw, getUnixTime());
emit
speedChanged
(
this
,
hud
.
airspeed
,
0.0
f
,
hud
.
climb
,
getUnixTime
());
}
break
;
...
...
src/ui/WaypointView.cc
View file @
e6ed6da3
...
...
@@ -35,14 +35,14 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
customCommand
->
setupUi
(
m_ui
->
customActionWidget
);
// add actions
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Navigate"
),
MAV_
ACTION_NAVIGATE
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"TakeOff"
),
MAV_
ACTION
_TAKEOFF
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Unlim."
),
MAV_
ACTION_LOITER
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Time"
),
MAV_
ACTION_LOITER_MAX
_TIME
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Turns"
),
MAV_
ACTION_LOITER_MAX
_TURNS
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Return to Launch"
),
MAV_
ACTION_RETURN
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Land"
),
MAV_
ACTION
_LAND
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Other"
),
MAV_
ACTION_NB
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Navigate"
),
MAV_
CMD_NAV_WAYPOINT
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"TakeOff"
),
MAV_
CMD_NAV
_TAKEOFF
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Unlim."
),
MAV_
CMD_NAV_LOITER_UNLIM
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Time"
),
MAV_
CMD_NAV_LOITER
_TIME
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Loiter Turns"
),
MAV_
CMD_NAV_LOITER
_TURNS
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Return to Launch"
),
MAV_
CMD_NAV_RETURN_TO_LAUNCH
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Land"
),
MAV_
CMD_NAV
_LAND
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"Other"
),
MAV_
COMMAND_ENUM_END
);
// m_ui->comboBox_action->addItem(tr("Delay"), MAV_ACTION_DELAY_BEFORE_COMMAND);
// m_ui->comboBox_action->addItem(tr("Ascend/Descent"), MAV_ACTION_ASCEND_AT_RATE);
// m_ui->comboBox_action->addItem(tr("Change Mode"), MAV_ACTION_CHANGE_MODE);
...
...
@@ -145,7 +145,7 @@ void WaypointView::updateActionView(int action)
switch
(
action
)
{
case
MAV_
ACTION
_TAKEOFF
:
case
MAV_
CMD_NAV
_TAKEOFF
:
m_ui
->
orbitSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
m_ui
->
turnsSpinBox
->
hide
();
...
...
@@ -155,7 +155,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
customActionWidget
->
hide
();
m_ui
->
takeOffAngleSpinBox
->
show
();
break
;
case
MAV_
ACTION
_LAND
:
case
MAV_
CMD_NAV
_LAND
:
m_ui
->
orbitSpinBox
->
hide
();
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
...
...
@@ -165,7 +165,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
break
;
case
MAV_
ACTION_RETURN
:
case
MAV_
CMD_NAV_RETURN_TO_LAUNCH
:
m_ui
->
orbitSpinBox
->
hide
();
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
...
...
@@ -175,7 +175,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
break
;
case
MAV_
ACTION_NAVIGATE
:
case
MAV_
CMD_NAV_WAYPOINT
:
m_ui
->
orbitSpinBox
->
hide
();
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
turnsSpinBox
->
hide
();
...
...
@@ -186,7 +186,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
acceptanceSpinBox
->
show
();
m_ui
->
yawSpinBox
->
show
();
break
;
case
MAV_
ACTION_LOITER
:
case
MAV_
CMD_NAV_LOITER_UNLIM
:
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
m_ui
->
turnsSpinBox
->
hide
();
...
...
@@ -196,7 +196,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
customActionWidget
->
hide
();
m_ui
->
orbitSpinBox
->
show
();
break
;
case
MAV_
ACTION_LOITER_MAX
_TURNS
:
case
MAV_
CMD_NAV_LOITER
_TURNS
:
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
m_ui
->
autoContinue
->
hide
();
...
...
@@ -206,7 +206,7 @@ void WaypointView::updateActionView(int action)
m_ui
->
orbitSpinBox
->
show
();
m_ui
->
turnsSpinBox
->
show
();
break
;
case
MAV_
ACTION_LOITER_MAX
_TIME
:
case
MAV_
CMD_NAV_LOITER
_TIME
:
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
m_ui
->
turnsSpinBox
->
hide
();
...
...
@@ -228,9 +228,9 @@ void WaypointView::changedAction(int index)
{
// set waypoint action
int
actionIndex
=
m_ui
->
comboBox_action
->
itemData
(
index
).
toUInt
();
if
(
actionIndex
<
MAV_
ACTION_NB
&&
actionIndex
>=
0
)
if
(
actionIndex
<
MAV_
COMMAND_ENUM_END
&&
actionIndex
>=
0
)
{
MAV_
ACTION
action
=
(
MAV_ACTION
)
actionIndex
;
MAV_
COMMAND
action
=
(
MAV_COMMAND
)
actionIndex
;
wp
->
setAction
(
action
);
}
...
...
@@ -240,24 +240,21 @@ void WaypointView::changedAction(int index)
switch
(
actionIndex
)
{
case
MAV_ACTION_TAKEOFF
:
case
MAV_ACTION_LAND
:
case
MAV_ACTION_RETURN
:
case
MAV_ACTION_NAVIGATE
:
case
MAV_ACTION_LOITER
:
case
MAV_ACTION_LOITER_MAX_TURNS
:
case
MAV_ACTION_LOITER_MAX_TIME
:
case
MAV_ACTION_DELAY_BEFORE_COMMAND
:
case
MAV_ACTION_CHANGE_MODE
:
case
MAV_ACTION_SET_ORIGIN
:
case
MAV_ACTION_RELAY_ON
:
case
MAV_ACTION_RELAY_OFF
:
case
MAV_CMD_NAV_TAKEOFF
:
case
MAV_CMD_NAV_LAND
:
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
case
MAV_CMD_NAV_WAYPOINT
:
case
MAV_CMD_NAV_LOITER_UNLIM
:
case
MAV_CMD_NAV_LOITER_TURNS
:
case
MAV_CMD_NAV_LOITER_TIME
:
case
MAV_CMD_NAV_DELAY
:
case
MAV_CMD_SYS_SET_MODE
:
// Back to global frame
if
(
wp
->
getFrame
()
==
MAV_FRAME_MISSION
)
changedFrame
(
0
);
// Update view
updateActionView
(
actionIndex
);
break
;
case
MAV_
ACTION_NB
:
case
MAV_
COMMAND_ENUM_END
:
default:
// Switch to mission frame
changedFrame
(
MAV_FRAME_MISSION
);
...
...
@@ -435,13 +432,13 @@ void WaypointView::updateValues()
}
switch
(
action
)
{
case
MAV_
ACTION
_TAKEOFF
:
case
MAV_
CMD_NAV
_TAKEOFF
:
break
;
case
MAV_
ACTION
_LAND
:
case
MAV_
CMD_NAV
_LAND
:
break
;
case
MAV_
ACTION_NAVIGATE
:
case
MAV_
CMD_NAV_WAYPOINT
:
break
;
case
MAV_
ACTION_LOITER
:
case
MAV_
CMD_NAV_LOITER_UNLIM
:
break
;
default:
std
::
cerr
<<
"unknown action"
<<
std
::
endl
;
...
...
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