mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: added MOT_BOOST_SCALE
this is to support boost motors for copters, such as having a petrol motor for extra lift on a multicopter The scaling factor allows the user to control how much of the lift is generated from the booster and how much from the main multicopter motors
This commit is contained in:
parent
2168222d4b
commit
bdc4320fe8
|
@ -162,6 +162,14 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
|||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SPOOL_TIME", 36, AP_MotorsMulticopter, _spool_up_time, AP_MOTORS_SPOOL_UP_TIME_DEFAULT),
|
||||
|
||||
// @Param: BOOST_SCALE
|
||||
// @DisplayName: Motor boost scale
|
||||
// @Description: This is a scaling factor for vehicles with a vertical booster motor used for extra lift. It is used with electric multicopters that have an internal combusion booster motor for longer endurance. The output to the BoostThrottle servo function is set to the current motor thottle times this scaling factor. A higher scaling factor will put more of the load on the booster motor. A value of 1 will set the BoostThrottle equal to the main throttle.
|
||||
// @Range: 0 5
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("BOOST_SCALE", 37, AP_MotorsMulticopter, _boost_scale, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -217,8 +225,21 @@ void AP_MotorsMulticopter::output()
|
|||
|
||||
// convert rpy_thrust values to pwm
|
||||
output_to_motors();
|
||||
|
||||
// output any booster throttle
|
||||
output_boost_throttle();
|
||||
};
|
||||
|
||||
// output booster throttle, if any
|
||||
void AP_MotorsMulticopter::output_boost_throttle(void)
|
||||
{
|
||||
if (_boost_scale > 0) {
|
||||
float throttle = constrain_float(get_throttle() * _boost_scale, 0, 1);
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, throttle*1000);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// sends minimum values out to the motors
|
||||
void AP_MotorsMulticopter::output_min()
|
||||
{
|
||||
|
|
|
@ -137,6 +137,9 @@ protected:
|
|||
// apply any thrust compensation for the frame
|
||||
virtual void thrust_compensation(void) {}
|
||||
|
||||
// output booster throttle, if any
|
||||
virtual void output_boost_throttle(void);
|
||||
|
||||
// save parameters as part of disarming
|
||||
void save_params_on_disarm();
|
||||
|
||||
|
@ -168,6 +171,9 @@ protected:
|
|||
|
||||
// time to spool motors to min throttle
|
||||
AP_Float _spool_up_time;
|
||||
|
||||
// scaling for booster motor throttle
|
||||
AP_Float _boost_scale;
|
||||
|
||||
// motor output variables
|
||||
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS]; // true if motor is enabled
|
||||
|
|
Loading…
Reference in New Issue