Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Heli: Add Autorotation Flare and Touch Down Phases #28420

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,14 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure)
passed = false;
}

#if FRAME_CONFIG == HELI_FRAME && MODE_AUTOROTATE_ENABLED
// check on autorotation config
if (!copter.g2.arot.arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
check_failed(display_failure, "AROT: %s", failure_msg);
passed = false;
}
#endif

// If not passed all checks return false
if (!passed) {
return false;
Expand Down
6 changes: 0 additions & 6 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -655,12 +655,6 @@ void Copter::twentyfive_hz_logging()
AP::ins().Write_IMU();
}

#if MODE_AUTOROTATE_ENABLED
if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) {
//update autorotation log
g2.arot.Log_Write_Autorotation();
}
#endif
#if HAL_GYROFFT_ENABLED
if (should_log(MASK_LOG_FTN_FAST)) {
gyro_fft.write_log_messages();
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -256,7 +256,7 @@ class Copter : public AP_Vehicle {
AP_SurfaceDistance rangefinder_up_state {ROTATION_PITCH_90, inertial_nav, 1U};

// helper function to get inertially interpolated rangefinder height.
bool get_rangefinder_height_interpolated_cm(int32_t& ret) const;
bool get_rangefinder_height_interpolated_cm(int32_t& ret);

#if AP_RANGEFINDER_ENABLED
class SurfaceTracking {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1273,7 +1273,7 @@ ParametersG2::ParametersG2(void)
,mode_systemid_ptr(&copter.mode_systemid)
#endif
#if MODE_AUTOROTATE_ENABLED
,arot()
,arot(copter.ahrs, copter.motors, copter.attitude_control, copter.inertial_nav)
#endif
#if HAL_BUTTON_ENABLED
,button_ptr(&copter.button)
Expand Down
39 changes: 9 additions & 30 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1993,6 +1993,7 @@ class ModeAutorotate : public Mode {

bool init(bool ignore_checks) override;
void run() override;
void exit() override;

bool is_autopilot() const override { return true; }
bool requires_GPS() const override { return false; }
Expand All @@ -2008,13 +2009,9 @@ class ModeAutorotate : public Mode {

private:

// --- Internal variables ---
float _initial_rpm; // Head speed recorded at initiation of flight mode (RPM)
float _target_head_speed; // The terget head main rotor head speed. Normalised by main rotor set point
float _desired_v_z; // Desired vertical
int32_t _pitch_target; // Target pitch attitude to pass to attitude controller
float _pitch_target; // Target pitch attitude to pass to attitude controller
uint32_t _entry_time_start_ms; // Time remaining until entry phase moves on to glide phase
float _hs_decay; // The head accerleration during the entry phase
uint32_t _last_logged; // Used for timeing slow rate autorotation log

enum class Autorotation_Phase {
ENTRY,
Expand All @@ -2023,31 +2020,13 @@ class ModeAutorotate : public Mode {
TOUCH_DOWN,
LANDED } phase_switch;

enum class Navigation_Decision {
USER_CONTROL_STABILISED,
STRAIGHT_AHEAD,
INTO_WIND,
NEAREST_RALLY} nav_pos_switch;

// --- Internal flags ---
struct controller_flags {
bool entry_initial : 1;
bool ss_glide_initial : 1;
bool flare_initial : 1;
bool touch_down_initial : 1;
bool landed_initial : 1;
bool straight_ahead_initial : 1;
bool level_initial : 1;
bool break_initial : 1;
bool bad_rpm : 1;
struct Controller_Flags {
bool entry_init : 1;
bool glide_init : 1;
bool flare_init : 1;
bool touch_down_init : 1;
bool landed_init : 1;
} _flags;

struct message_flags {
bool bad_rpm : 1;
} _msg_flags;

//--- Internal functions ---
void warning_message(uint8_t message_n); //Handles output messages to the terminal

};
#endif
Loading
Loading