Plane: fixed misspellings of 'transition'

This commit is contained in:
Henry Wurzburg 2022-06-29 07:35:55 -05:00 committed by Tom Pittenger
parent 215842fe82
commit 6bb567465a
6 changed files with 15 additions and 15 deletions

View File

@ -6,7 +6,7 @@
bool ModeQAcro::_enter() bool ModeQAcro::_enter()
{ {
quadplane.throttle_wait = false; quadplane.throttle_wait = false;
quadplane.transition->force_transistion_complete(); quadplane.transition->force_transition_complete();
attitude_control->relax_attitude_controllers(); attitude_control->relax_attitude_controllers();
return true; return true;
} }

View File

@ -756,7 +756,7 @@ bool QuadPlane::setup(void)
// init wp_nav variables after detaults are setup // init wp_nav variables after detaults are setup
wp_nav->wp_and_spline_init(); wp_nav->wp_and_spline_init();
transition->force_transistion_complete(); transition->force_transition_complete();
// param count will have changed // param count will have changed
AP_Param::invalidate_count(); AP_Param::invalidate_count();
@ -1747,7 +1747,7 @@ void QuadPlane::update(void)
set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
motors->output(); motors->output();
} }
transition->force_transistion_complete(); transition->force_transition_complete();
assisted_flight = false; assisted_flight = false;
} else { } else {
transition->update(); transition->update();
@ -3292,7 +3292,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()), climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()),
throttle_mix : attitude_control->get_throttle_mix(), throttle_mix : attitude_control->get_throttle_mix(),
speed_scaler : tailsitter.log_spd_scaler, speed_scaler : tailsitter.log_spd_scaler,
transition_state : transition->get_log_transision_state(), transition_state : transition->get_log_transition_state(),
assist : assisted_flight, assist : assisted_flight,
}; };
plane.logger.WriteBlock(&pkt, sizeof(pkt)); plane.logger.WriteBlock(&pkt, sizeof(pkt));
@ -4085,7 +4085,7 @@ void SLT_Transition::set_last_fw_pitch()
last_fw_nav_pitch_cd = plane.nav_pitch_cd; last_fw_nav_pitch_cd = plane.nav_pitch_cd;
} }
void SLT_Transition::force_transistion_complete() { void SLT_Transition::force_transition_complete() {
transition_state = TRANSITION_DONE; transition_state = TRANSITION_DONE;
in_forced_transition = false; in_forced_transition = false;
transition_start_ms = 0; transition_start_ms = 0;

View File

@ -832,7 +832,7 @@ void Tailsitter_Transition::VTOL_update()
if (transition_state == TRANSITION_ANGLE_WAIT_VTOL) { if (transition_state == TRANSITION_ANGLE_WAIT_VTOL) {
float aspeed; float aspeed;
bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed);
// provide assistance in forward flight portion of tailsitter transistion // provide assistance in forward flight portion of tailsitter transition
quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed);
if (!quadplane.tailsitter.transition_vtol_complete()) { if (!quadplane.tailsitter.transition_vtol_complete()) {
return; return;
@ -937,7 +937,7 @@ void Tailsitter_Transition::restart()
} }
// force state to FW and setup for the transition back to VTOL // force state to FW and setup for the transition back to VTOL
void Tailsitter_Transition::force_transistion_complete() void Tailsitter_Transition::force_transition_complete()
{ {
transition_state = TRANSITION_DONE; transition_state = TRANSITION_DONE;
vtol_transition_start_ms = AP_HAL::millis(); vtol_transition_start_ms = AP_HAL::millis();

View File

@ -54,7 +54,7 @@ public:
// check if we have completed transition to vtol // check if we have completed transition to vtol
bool transition_vtol_complete(void) const; bool transition_vtol_complete(void) const;
// return true if transistion to VTOL flight // return true if transition to VTOL flight
bool in_vtol_transition(uint32_t now = 0) const; bool in_vtol_transition(uint32_t now = 0) const;
// account for control surface speed scaling in VTOL modes // account for control surface speed scaling in VTOL modes
@ -144,14 +144,14 @@ public:
void VTOL_update() override; void VTOL_update() override;
void force_transistion_complete() override; void force_transition_complete() override;
bool complete() const override { return transition_state == TRANSITION_DONE; } bool complete() const override { return transition_state == TRANSITION_DONE; }
// setup for the transition back to fixed wing // setup for the transition back to fixed wing
void restart() override; void restart() override;
uint8_t get_log_transision_state() const override { return static_cast<uint8_t>(transition_state); } uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }
bool active() const override { return transition_state != TRANSITION_DONE; } bool active() const override { return transition_state != TRANSITION_DONE; }

View File

@ -74,7 +74,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = {
// @Param: WING_FLAP // @Param: WING_FLAP
// @DisplayName: Tiltrotor tilt angle that will be used as flap // @DisplayName: Tiltrotor tilt angle that will be used as flap
// @Description: For use on tilt wings, the wing will tilt up to this angle for flap, transistion will be complete when the wing reaches this angle from the forward fight position, 0 disables // @Description: For use on tilt wings, the wing will tilt up to this angle for flap, transition will be complete when the wing reaches this angle from the forward fight position, 0 disables
// @Units: deg // @Units: deg
// @Increment: 1 // @Increment: 1
// @Range: 0 15 // @Range: 0 15

View File

@ -28,13 +28,13 @@ public:
virtual void VTOL_update() = 0; virtual void VTOL_update() = 0;
virtual void force_transistion_complete() = 0; virtual void force_transition_complete() = 0;
virtual bool complete() const = 0; virtual bool complete() const = 0;
virtual void restart() = 0; virtual void restart() = 0;
virtual uint8_t get_log_transision_state() const = 0; virtual uint8_t get_log_transition_state() const = 0;
virtual bool active() const = 0; virtual bool active() const = 0;
@ -75,13 +75,13 @@ public:
void VTOL_update() override; void VTOL_update() override;
void force_transistion_complete() override; void force_transition_complete() override;
bool complete() const override { return transition_state == TRANSITION_DONE; } bool complete() const override { return transition_state == TRANSITION_DONE; }
void restart() override { transition_state = TRANSITION_AIRSPEED_WAIT; } void restart() override { transition_state = TRANSITION_AIRSPEED_WAIT; }
uint8_t get_log_transision_state() const override { return static_cast<uint8_t>(transition_state); } uint8_t get_log_transition_state() const override { return static_cast<uint8_t>(transition_state); }
bool active() const override; bool active() const override;