From 5fcd2de4fa2233722251542455c6fcde70b41012 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 15 Apr 2021 13:14:12 +0900 Subject: [PATCH] Copter: attitude target thrust-as-thrust bit moved from DEV_OPTIONS to GUID_OPTIONS --- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/defines.h | 1 - ArduCopter/mode.h | 4 ++++ ArduCopter/mode_guided.cpp | 6 ++++++ 5 files changed, 13 insertions(+), 4 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 8552cce0b6..8b62022db4 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1058,7 +1058,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) } // check if the message's thrust field should be interpreted as a climb rate or as thrust - const bool use_thrust = copter.g2.dev_options.get() & DevOptionSetAttitudeTarget_ThrustAsThrust; + const bool use_thrust = copter.mode_guided.set_attitude_target_provides_thrust(); float climb_rate_or_thrust; if (use_thrust) { diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 7bd4589e88..8ee4f0b844 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -813,7 +813,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: DEV_OPTIONS // @DisplayName: Development options // @Description: Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning - // @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt,2:SetAttitudeTarget_ThrustAsThrust + // @Bitmask: 0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt // @User: Advanced AP_GROUPINFO("DEV_OPTIONS", 7, ParametersG2, dev_options, 0), @@ -1026,7 +1026,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: GUID_OPTIONS // @DisplayName: Guided mode options // @Description: Options that can be applied to change guided mode behaviour - // @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw + // @Bitmask: 0:Allow Arming from Transmitter,2:Ignore pilot yaw,3:SetAttitudeTarget_ThrustAsThrust // @User: Advanced AP_GROUPINFO("GUID_OPTIONS", 41, ParametersG2, guided_options, 0), #endif diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index cd8763b15b..a03ae3bbd1 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -131,7 +131,6 @@ enum PayloadPlaceStateType { enum DevOptions { DevOptionADSBMAVLink = 1, DevOptionVFR_HUDRelativeAlt = 2, - DevOptionSetAttitudeTarget_ThrustAsThrust = 4, }; // Logging parameters diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 6c84033401..64533112de 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -837,6 +837,9 @@ public: void set_velocity(const Vector3f& velocity, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false, bool log_request = true); bool set_destination_posvel(const Vector3f& destination, const Vector3f& velocity, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false); + // returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate + bool set_attitude_target_provides_thrust() const; + void limit_clear(); void limit_init_time_and_pos(); void limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm); @@ -875,6 +878,7 @@ private: AllowArmingFromTX = (1U << 0), // this bit is still available, pilot yaw was mapped to bit 2 for symmetry with auto IgnorePilotYaw = (1U << 2), + SetAttitudeTarget_ThrustAsThrust = (1U << 3), }; void pos_control_start(); diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index b66d49d8a2..74fbd03abd 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -367,6 +367,12 @@ bool ModeGuided::set_destination_posvel(const Vector3f& destination, const Vecto return true; } +// returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate +bool ModeGuided::set_attitude_target_provides_thrust() const +{ + return ((copter.g2.guided_options.get() & uint32_t(Options::SetAttitudeTarget_ThrustAsThrust)) != 0); +} + // set guided mode angle target and climbrate void ModeGuided::set_angle(const Quaternion &q, float climb_rate_cms_or_thrust, bool use_yaw_rate, float yaw_rate_rads, bool use_thrust) {