mirror of https://github.com/ArduPilot/ardupilot
AP_SmartRTL: Add option to ignore pilot yaw
This commit is contained in:
parent
1e1be590e2
commit
d928b80629
|
@ -36,6 +36,13 @@ const AP_Param::GroupInfo AP_SmartRTL::var_info[] = {
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("POINTS", 1, AP_SmartRTL, _points_max, SMARTRTL_POINTS_DEFAULT),
|
AP_GROUPINFO("POINTS", 1, AP_SmartRTL, _points_max, SMARTRTL_POINTS_DEFAULT),
|
||||||
|
|
||||||
|
// @Param: OPTIONS
|
||||||
|
// @DisplayName: SmartRTL options
|
||||||
|
// @Description: Bitmask of SmartRTL options.
|
||||||
|
// @Bitmask: 2:Ignore pilot yaw
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("OPTIONS", 2, AP_SmartRTL, _options, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -861,3 +868,10 @@ bool AP_SmartRTL::loops_overlap(const prune_loop_t &loop1, const prune_loop_t &l
|
||||||
// if we got here, no overlap
|
// if we got here, no overlap
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// returns true if pilot's yaw input should be used to adjust vehicle's heading
|
||||||
|
bool AP_SmartRTL::use_pilot_yaw(void) const
|
||||||
|
{
|
||||||
|
return (_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
|
@ -74,6 +74,9 @@ public:
|
||||||
// run background cleanup - should be run regularly from the IO thread
|
// run background cleanup - should be run regularly from the IO thread
|
||||||
void run_background_cleanup();
|
void run_background_cleanup();
|
||||||
|
|
||||||
|
// returns true if pilot's yaw input should be used to adjust vehicle's heading
|
||||||
|
bool use_pilot_yaw(void) const;
|
||||||
|
|
||||||
// parameter var table
|
// parameter var table
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
@ -94,6 +97,12 @@ private:
|
||||||
SRTL_DEACTIVATED_PROGRAM_ERROR,
|
SRTL_DEACTIVATED_PROGRAM_ERROR,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// enum for SRTL_OPTIONS parameter
|
||||||
|
enum class Options : int32_t {
|
||||||
|
// bits 1 and 2 are still available, pilot yaw was mapped to bit 2 for symmetry with auto
|
||||||
|
IgnorePilotYaw = (1U << 2),
|
||||||
|
};
|
||||||
|
|
||||||
// add point to end of path
|
// add point to end of path
|
||||||
bool add_point(const Vector3f& point);
|
bool add_point(const Vector3f& point);
|
||||||
|
|
||||||
|
@ -164,6 +173,7 @@ private:
|
||||||
// parameters
|
// parameters
|
||||||
AP_Float _accuracy;
|
AP_Float _accuracy;
|
||||||
AP_Int16 _points_max;
|
AP_Int16 _points_max;
|
||||||
|
AP_Int32 _options;
|
||||||
|
|
||||||
// SmartRTL State Variables
|
// SmartRTL State Variables
|
||||||
bool _active; // true if SmartRTL is usable. may become unusable if the path becomes too long to keep in memory, and too convoluted to be cleaned up, SmartRTL will be permanently deactivated (for the remainder of the flight)
|
bool _active; // true if SmartRTL is usable. may become unusable if the path becomes too long to keep in memory, and too convoluted to be cleaned up, SmartRTL will be permanently deactivated (for the remainder of the flight)
|
||||||
|
|
Loading…
Reference in New Issue