Browse Source

Plane: fixed misspellings of 'transition'

apm_2208
Henry Wurzburg 3 years ago committed by Tom Pittenger
parent
commit
6bb567465a
  1. 2
      ArduPlane/mode_qacro.cpp
  2. 8
      ArduPlane/quadplane.cpp
  3. 4
      ArduPlane/tailsitter.cpp
  4. 6
      ArduPlane/tailsitter.h
  5. 2
      ArduPlane/tiltrotor.cpp
  6. 8
      ArduPlane/transition.h

2
ArduPlane/mode_qacro.cpp

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

8
ArduPlane/quadplane.cpp

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

4
ArduPlane/tailsitter.cpp

@ -832,7 +832,7 @@ void Tailsitter_Transition::VTOL_update() @@ -832,7 +832,7 @@ void Tailsitter_Transition::VTOL_update()
if (transition_state == TRANSITION_ANGLE_WAIT_VTOL) {
float 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);
if (!quadplane.tailsitter.transition_vtol_complete()) {
return;
@ -937,7 +937,7 @@ void Tailsitter_Transition::restart() @@ -937,7 +937,7 @@ void Tailsitter_Transition::restart()
}
// 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;
vtol_transition_start_ms = AP_HAL::millis();

6
ArduPlane/tailsitter.h

@ -54,7 +54,7 @@ public: @@ -54,7 +54,7 @@ public:
// check if we have completed transition to vtol
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;
// account for control surface speed scaling in VTOL modes
@ -144,14 +144,14 @@ public: @@ -144,14 +144,14 @@ public:
void VTOL_update() override;
void force_transistion_complete() override;
void force_transition_complete() override;
bool complete() const override { return transition_state == TRANSITION_DONE; }
// setup for the transition back to fixed wing
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; }

2
ArduPlane/tiltrotor.cpp

@ -74,7 +74,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = { @@ -74,7 +74,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = {
// @Param: WING_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
// @Increment: 1
// @Range: 0 15

8
ArduPlane/transition.h

@ -28,13 +28,13 @@ public: @@ -28,13 +28,13 @@ public:
virtual void VTOL_update() = 0;
virtual void force_transistion_complete() = 0;
virtual void force_transition_complete() = 0;
virtual bool complete() const = 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;
@ -75,13 +75,13 @@ public: @@ -75,13 +75,13 @@ public:
void VTOL_update() override;
void force_transistion_complete() override;
void force_transition_complete() override;
bool complete() const override { return transition_state == TRANSITION_DONE; }
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;

Loading…
Cancel
Save