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

Plane: add option to use boost motor in forward flight, tiltrotors and tailsitters only #12865

Closed
wants to merge 2 commits into from
Closed
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
2 changes: 1 addition & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,7 +329,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: OPTIONS
// @DisplayName: quadplane options
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the corrent position. When Use QRTL is set it will replace QLAND with QRTL for failsafe actions when in VTOL modes.
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes,6:Use idle governor in MANUAL,7:Use boost motor in forward flight (tiltrotors and tailsitters only)
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),

AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -531,6 +531,7 @@ class QuadPlane
OPTION_MISSION_LAND_FW_APPROACH=(1<<4),
OPTION_FS_QRTL=(1<<5),
OPTION_IDLE_GOV_MANUAL=(1<<6),
OPTION_BOOST_FORWARD_FLIGHT=(1<<7),
};

AP_Float takeoff_failure_scalar;
Expand Down
3 changes: 2 additions & 1 deletion ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,8 @@ void QuadPlane::tailsitter_output(void)
}
}
// set AP_MotorsMatrix throttles for forward flight
motors->output_motor_mask(throttle * 0.01f, mask, plane.rudder_dt);
const bool use_boost = (options & OPTION_BOOST_FORWARD_FLIGHT) != 0;
motors->output_motor_mask(throttle * 0.01f, mask, plane.rudder_dt, use_boost);
return;
}

Expand Down
12 changes: 8 additions & 4 deletions ArduPlane/tiltrotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,11 @@ void QuadPlane::tiltrotor_continuous_update(void)
}
if (!motor_test.running) {
// the motors are all the way forward, start using them for fwd thrust
uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get();
motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt);
const uint8_t mask = is_zero(tilt.current_throttle)?0:(uint8_t)tilt.tilt_mask.get();
const bool use_boost = (options & OPTION_BOOST_FORWARD_FLIGHT) != 0;
motors->output_motor_mask(tilt.current_throttle, mask, plane.rudder_dt, use_boost);
// prevent motor shutdown
tilt.motors_active = true;
}
return;
}
Expand Down Expand Up @@ -163,9 +166,10 @@ void QuadPlane::tiltrotor_binary_update(void)

float new_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01f;
if (tilt.current_tilt >= 1) {
uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get();
const uint8_t mask = is_zero(new_throttle)?0:(uint8_t)tilt.tilt_mask.get();
// the motors are all the way forward, start using them for fwd thrust
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt);
const bool use_boost = (options & OPTION_BOOST_FORWARD_FLIGHT) != 0;
motors->output_motor_mask(new_throttle, mask, plane.rudder_dt, use_boost);
}
} else {
tiltrotor_binary_slew(false);
Expand Down
10 changes: 9 additions & 1 deletion libraries/AP_Motors/AP_MotorsMulticopter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -751,7 +751,7 @@ void AP_MotorsMulticopter::set_throttle_passthrough_for_esc_calibration(float th
// output a thrust to all motors that match a given motor mask. This
// is used to control tiltrotor motors in forward flight. Thrust is in
// the range 0 to 1
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float rudder_dt, bool use_boost)
{
const int16_t pwm_min = get_pwm_output_min();
const int16_t pwm_range = get_pwm_output_max() - pwm_min;
Expand All @@ -773,6 +773,14 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r
}
}
}

// Output to boost motor
if (use_boost) {
// boost throttle is in the range 0 to 1000
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, thrust * 1000);
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, 0);
}
}

// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsMulticopter.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class AP_MotorsMulticopter : public AP_Motors {
// output a thrust to all motors that match a given motor
// mask. This is used to control tiltrotor motors in forward
// flight. Thrust is in the range 0 to 1
virtual void output_motor_mask(float thrust, uint8_t mask, float rudder_dt);
virtual void output_motor_mask(float thrust, uint8_t mask, float rudder_dt, bool use_boost);

// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Motors/AP_MotorsTri.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -338,10 +338,10 @@ void AP_MotorsTri::thrust_compensation(void)
/*
override tricopter tail servo output in output_motor_mask
*/
void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
void AP_MotorsTri::output_motor_mask(float thrust, uint8_t mask, float rudder_dt, bool use_boost)
{
// normal multicopter output
AP_MotorsMulticopter::output_motor_mask(thrust, mask, rudder_dt);
AP_MotorsMulticopter::output_motor_mask(thrust, mask, rudder_dt, use_boost);

// and override yaw servo
rc_write_angle(AP_MOTORS_CH_TRI_YAW, 0);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Motors/AP_MotorsTri.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class AP_MotorsTri : public AP_MotorsMulticopter {
// mask. This is used to control tiltrotor motors in forward
// flight. Thrust is in the range 0 to 1
// rudder_dt applys diffential thrust for yaw in the range 0 to 1
void output_motor_mask(float thrust, uint8_t mask, float rudder_dt) override;
void output_motor_mask(float thrust, uint8_t mask, float rudder_dt, bool use_boost) override;

// return the roll factor of any motor, this is used for tilt rotors and tail sitters
// using copter motors for forward flight
Expand Down