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
630f9e56
Commit
630f9e56
authored
Jul 31, 2020
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
aece8fa6
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
5 additions
and
34 deletions
+5
-34
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+0
-13
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+0
-1
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+0
-5
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+0
-3
MavCmdInfoMultiRotor.json
src/MissionManager/MavCmdInfoMultiRotor.json
+5
-0
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+0
-4
Vehicle.cc
src/Vehicle/Vehicle.cc
+0
-5
Vehicle.h
src/Vehicle/Vehicle.h
+0
-3
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
630f9e56
...
...
@@ -134,19 +134,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
return
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
"FRAME"
)
->
rawValue
().
toInt
()
!=
0
;
}
bool
ArduCopterFirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
isOfflineEditingVehicle
())
{
return
FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
vehicle
);
}
else
{
if
(
vehicle
->
multiRotor
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
!=
0
;
}
}
return
true
;
}
#if 0
// Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
630f9e56
...
...
@@ -71,7 +71,6 @@ public:
QString
landFlightMode
(
void
)
const
override
{
return
QStringLiteral
(
"Land"
);
}
QString
takeControlFlightMode
(
void
)
const
override
{
return
QStringLiteral
(
"Loiter"
);
}
QString
followFlightMode
(
void
)
const
override
{
return
QStringLiteral
(
"Follow"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"DISARM_DELAY"
);
}
bool
supportsSmartRTL
(
void
)
const
override
{
return
true
;
}
#if 0
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
630f9e56
...
...
@@ -698,11 +698,6 @@ QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) {
return
nullptr
;
}
bool
FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
return
vehicle
->
multiRotor
()
?
false
:
true
;
}
bool
FirmwarePlugin
::
_armVehicleAndValidate
(
Vehicle
*
vehicle
)
{
if
(
vehicle
->
armed
())
{
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
630f9e56
...
...
@@ -297,9 +297,6 @@ public:
/// Returns a pointer to a dictionary of firmware-specific FactGroups
virtual
QMap
<
QString
,
FactGroup
*>*
factGroups
(
void
);
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
virtual
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
;
/// Returns the data needed to do battery consumption calculations
/// @param[out] mAhBattery Battery milliamp-hours rating (0 for no battery data available)
/// @param[out] hoverAmps Current draw in amps during hover
...
...
src/MissionManager/MavCmdInfoMultiRotor.json
View file @
630f9e56
...
...
@@ -9,6 +9,11 @@
"comment"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"paramRemove"
:
"3"
},
{
"id"
:
18
,
"comment"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"paramRemove"
:
"1,2,3,4"
},
{
"id"
:
19
,
"comment"
:
"MAV_CMD_NAV_LOITER_TIME"
,
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
630f9e56
...
...
@@ -501,10 +501,6 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
if
(
!
firmwareVehicle
)
{
firmwareVehicle
=
_controllerVehicle
;
}
bool
hideWaypointHeading
=
(
command
==
MAV_CMD_NAV_WAYPOINT
||
command
==
MAV_CMD_NAV_TAKEOFF
)
&&
(
i
==
4
)
&&
firmwareVehicle
->
firmwarePlugin
()
->
vehicleYawsToNextWaypointInMission
(
firmwareVehicle
);
if
(
hideWaypointHeading
)
{
continue
;
}
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
FactMetaData
*
paramMetaData
=
rgParamMetaData
[
i
-
1
];
...
...
src/Vehicle/Vehicle.cc
View file @
630f9e56
...
...
@@ -3835,11 +3835,6 @@ const QVariantList& Vehicle::staticCameraList() const
return
emptyList
;
}
bool
Vehicle
::
vehicleYawsToNextWaypointInMission
()
const
{
return
_firmwarePlugin
->
vehicleYawsToNextWaypointInMission
(
this
);
}
void
Vehicle
::
_setupAutoDisarmSignalling
()
{
QString
param
=
_firmwarePlugin
->
autoDisarmParameter
(
this
);
...
...
src/Vehicle/Vehicle.h
View file @
630f9e56
...
...
@@ -1125,9 +1125,6 @@ public:
QGCCameraManager
*
dynamicCameras
()
{
return
_cameras
;
}
QString
hobbsMeter
();
/// @true: When flying a mission the vehicle is always facing towards the next waypoint
bool
vehicleYawsToNextWaypointInMission
()
const
;
/// The vehicle is responsible for making the initial request for the Plan.
/// @return: true: initial request is complete, false: initial request is still in progress;
bool
initialPlanRequestComplete
()
const
{
return
_initialPlanRequestComplete
;
}
...
...
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