mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: Added DDS Method for Arming/Disarming
This commit is contained in:
parent
7f8df080f8
commit
5f17e33b39
@ -623,7 +623,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||||||
const char *rc_item = "Throttle";
|
const char *rc_item = "Throttle";
|
||||||
#endif
|
#endif
|
||||||
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
|
// check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto
|
||||||
if (!((method == AP_Arming::Method::MAVLINK || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
|
if (!((AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
|
||||||
// above top of deadband is too always high
|
// above top of deadband is too always high
|
||||||
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
|
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
|
||||||
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
|
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
|
||||||
@ -790,7 +790,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che
|
|||||||
|
|
||||||
// do not allow disarm via mavlink if we think we are flying:
|
// do not allow disarm via mavlink if we think we are flying:
|
||||||
if (do_disarm_checks &&
|
if (do_disarm_checks &&
|
||||||
method == AP_Arming::Method::MAVLINK &&
|
AP_Arming::method_is_GCS(method) &&
|
||||||
!copter.ap.land_complete) {
|
!copter.ap.land_complete) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -100,7 +100,7 @@ void ModeGuided::run()
|
|||||||
bool ModeGuided::allows_arming(AP_Arming::Method method) const
|
bool ModeGuided::allows_arming(AP_Arming::Method method) const
|
||||||
{
|
{
|
||||||
// always allow arming from the ground station or scripting
|
// always allow arming from the ground station or scripting
|
||||||
if (method == AP_Arming::Method::MAVLINK || method == AP_Arming::Method::SCRIPTING) {
|
if (AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -325,7 +325,7 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
|
|||||||
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
||||||
{
|
{
|
||||||
if (do_disarm_checks &&
|
if (do_disarm_checks &&
|
||||||
(method == AP_Arming::Method::MAVLINK ||
|
(AP_Arming::method_is_GCS(method) ||
|
||||||
method == AP_Arming::Method::RUDDER)) {
|
method == AP_Arming::Method::RUDDER)) {
|
||||||
if (plane.is_flying()) {
|
if (plane.is_flying()) {
|
||||||
// don't allow mavlink or rudder disarm while flying
|
// don't allow mavlink or rudder disarm while flying
|
||||||
|
@ -1832,6 +1832,7 @@ void AP_Arming::check_forced_logging(const AP_Arming::Method method)
|
|||||||
case Method::TOYMODELANDTHROTTLE:
|
case Method::TOYMODELANDTHROTTLE:
|
||||||
case Method::TOYMODELANDFORCE:
|
case Method::TOYMODELANDFORCE:
|
||||||
case Method::LANDING:
|
case Method::LANDING:
|
||||||
|
case Method::DDS:
|
||||||
case Method::UNKNOWN:
|
case Method::UNKNOWN:
|
||||||
AP::logger().set_long_log_persist(false);
|
AP::logger().set_long_log_persist(false);
|
||||||
return;
|
return;
|
||||||
|
@ -78,6 +78,7 @@ public:
|
|||||||
LANDING = 32, // only disarm uses this...
|
LANDING = 32, // only disarm uses this...
|
||||||
DEADRECKON_FAILSAFE = 33, // only disarm uses this...
|
DEADRECKON_FAILSAFE = 33, // only disarm uses this...
|
||||||
BLACKBOX = 34,
|
BLACKBOX = 34,
|
||||||
|
DDS = 35,
|
||||||
UNKNOWN = 100,
|
UNKNOWN = 100,
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -144,6 +145,9 @@ public:
|
|||||||
return (_arming_options & uint32_t(option)) != 0;
|
return (_arming_options & uint32_t(option)) != 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool method_is_GCS(Method method) {
|
||||||
|
return (method == Method::MAVLINK || method == Method::DDS);
|
||||||
|
}
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
|
Loading…
Reference in New Issue
Block a user