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

4.2 autorotation #3

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open

4.2 autorotation #3

wants to merge 4 commits into from

Conversation

bnsgeyer
Copy link
Owner

Allows me to see combined changes without putting a PR against the Ardupilot repo

@@ -125,7 +125,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(auto_disarm_check, 10, 50, 27),
SCHED_TASK(auto_trim, 10, 75, 30),
#if RANGEFINDER_ENABLED == ENABLED
SCHED_TASK(read_rangefinder, 20, 100, 33),
SCHED_TASK(read_rangefinder, 100, 100, 33),

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think we will get away with a straight change to 100 Hz. I think the best we can hope for is to make this a param value that defaults to 20.

{
_current_rpm = get_rpm(true);
if ((_param_head_speed_set_point - _current_rpm) >=0){
_rpm_decay = constrain_float((_param_head_speed_set_point - _current_rpm)/400.0f, 0.0f, 1.0f);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We shouldn't assume 400Hz

float pitch_vel2 = MIN(fabsf(pitch_vel), 2000);
pilot_yaw_rate = ((float)pilot_roll/1.0f) * (1.0f - (pitch_vel2 / 5000.0f)) * g2.acro_y_rate; //****THIS NEEDS FIXED*****

roll_vel = constrain_float(roll_vel, -560.0f, 560.0f);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We shouldn't hard code constrains. We also don't need to. The user defined input shaping will be done in the attitude control library

float pitch_vel = vel.y * ahrs.sin_yaw() + vel.x * ahrs.cos_yaw(); // body pitch vel

// gain scheduling for yaw
float pitch_vel2 = MIN(fabsf(pitch_vel), 2000);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would really like to try the weather vaneing library for doing the coordinated turns. Would reduce this code and minimise duplication.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yes, this was to do some testing of the control logic. Having the nose aligned onto velocity vector would be a great improvement both for avoiding sideslip during glide and for precise skid aligning during landing.

@@ -66,6 +61,10 @@ bool ModeAutorotate::init(bool ignore_checks)

// The decay rate to reduce the head speed from the current to the target
_hs_decay = ((_initial_rpm/g2.arot.get_hs_set_point()) - HEAD_SPEED_TARGET_RATIO) / AUTOROTATE_ENTRY_TIME;

//set motors to idle
copter.ap.motor_interlock_switch = false;

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks like a big no no to me. We should not be setting the interlock from the code. Why do we need to do this anyway?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is specific for ICE in case of "real" emergency. It is safer to have the ECU set to throttle-off position in case of in-flight shutdown/flameout.

_accel_target = _vel_p ;

// filter correction acceleration
_accel_target_filter.set_cutoff_frequency(10.0f);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't think we should be hard coding filters. Depends very much on the users setup as to what cutt offs should be set.

_accel_target = _accel_out_last + _accel_max;
} else if (_accel_target < _accel_out_last - _accel_max) {
_accel_target = _accel_out_last - _accel_max;
}

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit pick: can just use a constrain here

_control_output = constrain_float( _rsc_arot_bailout_pct/100.0f , 0.0f, 0.4f);
_control_output = constrain_float( _ext_gov_arot_pct/100.0f , 0.0f, 0.4f);
if(!_autorotating){
gcs().send_text(MAV_SEVERITY_CRITICAL, "Autorotation");

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't think we should be doing this at the motors level. This should be up at vehicle level

_rotor_ramp_output = _rotor_runup_output;
if (_use_bailout_ramp){
if(!_bailing_out){
gcs().send_text(MAV_SEVERITY_CRITICAL, "bailing_out");

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Again, not sure this is a motors level thing. We should put this stuff up in heli. Also not MAV_SEVERITY_CRITICAL

if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) {
_tail_rotor.set_autorotation_flag(_heliflags.in_autorotation);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Surely we don't need to change tail rotor ramp? It should not have spooled down

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the tail type is not right here. The spool down for tail motors should happen only for the direct drive fixed pitch.

@bnsgeyer bnsgeyer force-pushed the 4.2_autorotation branch 2 times, most recently from c179b89 to 17677f1 Compare April 27, 2022 02:21
Copy link
Owner Author

@bnsgeyer bnsgeyer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My first round of reviews. Looked mainly at files changed in the Arducopter folder. Will provide follow on reviews for the remaining files.

@@ -205,31 +205,38 @@ void Copter::heli_update_autorotation()
}
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it ok that the autorotate mode is set every time this method is ran. I'm guessing the set_mode method just ignores this since the mode is already set?

int32_t gnd_dist = flightmode->get_alt_above_ground_cm();

// use rangefinder if available
switch (rangefinder.status_orient(ROTATION_PITCH_270)) {
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

would this orientation always be ROTATION_PITCH_270 for downward facing? This sounds like it could be setup specific?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it is always ROTATION_PITCH_270 for downward facing rangefinders ( RNGFNDx_ORIENT = 25)

@@ -134,25 +193,29 @@ void ModeAutorotate::run()

}

// Slowly change the target head speed until the target head speed matches the parameter defined value
if (g2.arot.get_rpm() > HEAD_SPEED_TARGET_RATIO*1.005f || g2.arot.get_rpm() < HEAD_SPEED_TARGET_RATIO*0.995f) {
if(!hover_autorotation){
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be good that you put a comment in here that explains what is being done in this logic for whether it is a hover autorotation or not.

// Set target head speed in head speed controller
g2.arot.set_target_head_speed(_target_head_speed);
// Run airspeed/attitude controller
g2.arot.set_dt(G_Dt);
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is Dt being set here? Why not initialize the library with Dt? just wondering if we need to set Dt on every cycle. Could put dt as a argument for the update_forward_speed_controller.

// Retrieve pitch target
_pitch_target = g2.arot.get_pitch();
// Update controllers
_flags.bad_rpm = g2.arot.update_hs_glide_controller(G_Dt); //run head speed/ collective controller
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Dt is passed to the Update_hs_glide_controller here. Seems like Dt should be passed in initially and then it doesn't need to be here.

Copy link
Owner Author

@bnsgeyer bnsgeyer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Finished my review. Once we have addressed my comments then I will put in a PR and get randy involved

#define AP_FW_VEL_FF 0.15f
#define AP_FLARE_ALT 800
#define AP_T_TO_G 0.55f
#define GUIDED 0


const AP_Param::GroupInfo AC_Autorotation::var_info[] = {
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ENABLE param has the wrong DisplayName
Need to discuss parameter names
consistency with abbreviation for Bail out in names (BAIL vs BLOUT)
consistent with abbreviating Target with other libraries (TGT vs TARG)
T_TO_G maybe this should be TIME_GND
FW_V_FF maybe this should be FWD_VEL_FF
FW_V_P maybe this should be FWD_VEL_P
AS_ACC_MAX maybe this should be FWD_ACC_MAX (we get 16 char so this would be 16 with the AROT_)

if (_rotor_runup_output < _rotor_ramp_output) {
_rotor_runup_output = _rotor_ramp_output;
}
_rotor_runup_output = _rotor_ramp_output;
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is not allowed. the Run up timer must count down to allow rotor rundown on the ground to judge when it is safe to disarm.

_main_rotor.set_autorotation_flag(_heliflags.in_autorotation);
// set bailout ramp time
_main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
_tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout);
Copy link
Owner Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why is this set here and also in the if statement below. I need to understand when this needs to be used. Is this covering practice autorotations. I guess if it is a bailout then yes. So are we assuming that the DDVP will have the tail rotor shutdown during practice autorotation?

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This follows the original implementation, I don't thinkf DDVP tail rotor should be shut down in autorotation (whether practice or autonomous), directional control shall always be allowed.
The only case in which tail rotor should be shutdown is DDFP, as it relies on main rotor torque to achieve control in both directions

@bnsgeyer bnsgeyer force-pushed the 4.2_autorotation branch 2 times, most recently from 3805b6f to 2b458fb Compare December 15, 2023 23:35
@bnsgeyer bnsgeyer changed the base branch from Copter-4.2 to master December 15, 2023 23:39
bnsgeyer pushed a commit that referenced this pull request May 14, 2024
* Update SIM_StratoBlimp.cpp

* Update SIM_StratoBlimp.h
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants