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
88ae35fd
Commit
88ae35fd
authored
Oct 23, 2019
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add code to stop and monitor ROI mode.
parent
00e9317b
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
53 additions
and
0 deletions
+53
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+48
-0
Vehicle.h
src/Vehicle/Vehicle.h
+5
-0
No files found.
src/Vehicle/Vehicle.cc
View file @
88ae35fd
...
...
@@ -3133,6 +3133,40 @@ void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
}
}
void
Vehicle
::
stopGuidedModeROI
()
{
if
(
!
roiModeSupported
())
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"ROI mode not supported by Vehicle."
));
return
;
}
if
(
capabilityBits
()
&
MAV_PROTOCOL_CAPABILITY_COMMAND_INT
)
{
sendMavCommandInt
(
defaultComponentId
(),
MAV_CMD_DO_SET_ROI_NONE
,
MAV_FRAME_GLOBAL
,
true
,
// show error if fails
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
double
>
(
qQNaN
()),
// Empty
static_cast
<
double
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()));
// Empty
}
else
{
sendMavCommand
(
defaultComponentId
(),
MAV_CMD_DO_SET_ROI_NONE
,
true
,
// show error if fails
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()),
// Empty
static_cast
<
float
>
(
qQNaN
()));
// Empty
}
}
void
Vehicle
::
pauseVehicle
(
void
)
{
if
(
!
pauseVehicleSupported
())
{
...
...
@@ -3401,6 +3435,20 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
}
}
if
(
ack
.
command
==
MAV_CMD_DO_SET_ROI_LOCATION
)
{
if
(
ack
.
result
==
MAV_RESULT_ACCEPTED
)
{
_isROIEnabled
=
true
;
emit
isROIEnabledChanged
();
}
}
if
(
ack
.
command
==
MAV_CMD_DO_SET_ROI_NONE
)
{
if
(
ack
.
result
==
MAV_RESULT_ACCEPTED
)
{
_isROIEnabled
=
false
;
emit
isROIEnabledChanged
();
}
}
#if !defined(NO_ARDUPILOT_DIALECT)
if
(
ack
.
command
==
MAV_CMD_FLASH_BOOTLOADER
&&
ack
.
result
==
MAV_RESULT_ACCEPTED
)
{
qgcApp
()
->
showMessage
(
tr
(
"Bootloader flash succeeded"
));
...
...
src/Vehicle/Vehicle.h
View file @
88ae35fd
...
...
@@ -642,6 +642,7 @@ public:
Q_PROPERTY
(
qreal
gimbalPitch
READ
gimbalPitch
NOTIFY
gimbalPitchChanged
)
Q_PROPERTY
(
qreal
gimbalYaw
READ
gimbalYaw
NOTIFY
gimbalYawChanged
)
Q_PROPERTY
(
bool
gimbalData
READ
gimbalData
NOTIFY
gimbalDataChanged
)
Q_PROPERTY
(
bool
isROIEnabled
READ
isROIEnabled
NOTIFY
isROIEnabledChanged
)
// The following properties relate to Orbit status
Q_PROPERTY
(
bool
orbitActive
READ
orbitActive
NOTIFY
orbitActiveChanged
)
...
...
@@ -741,6 +742,7 @@ public:
/// Command vehicle to keep given point as ROI
/// @param centerCoord ROI coordinates
Q_INVOKABLE
void
guidedModeROI
(
const
QGeoCoordinate
&
centerCoord
);
Q_INVOKABLE
void
stopGuidedModeROI
();
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
...
...
@@ -1114,6 +1116,7 @@ public:
qreal
gimbalPitch
()
{
return
static_cast
<
qreal
>
(
_curGimbalPitch
);
}
qreal
gimbalYaw
()
{
return
static_cast
<
qreal
>
(
_curGinmbalYaw
);
}
bool
gimbalData
()
{
return
_haveGimbalData
;
}
bool
isROIEnabled
()
{
return
_isROIEnabled
;
}
public
slots
:
void
setVtolInFwdFlight
(
bool
vtolInFwdFlight
);
...
...
@@ -1229,6 +1232,7 @@ signals:
void
gimbalPitchChanged
();
void
gimbalYawChanged
();
void
gimbalDataChanged
();
void
isROIEnabledChanged
();
private
slots
:
void
_mavlinkMessageReceived
(
LinkInterface
*
link
,
mavlink_message_t
message
);
...
...
@@ -1495,6 +1499,7 @@ private:
float
_curGimbalPitch
=
0
.
0
f
;
float
_curGinmbalYaw
=
0
.
0
f
;
bool
_haveGimbalData
=
false
;
bool
_isROIEnabled
=
false
;
Joystick
*
_activeJoystick
=
nullptr
;
int
_firmwareMajorVersion
;
...
...
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