AP_Periph: added ESC_PWM_TYPE

this allows for oneshot and dshot on AP_Periph ESCs
This commit is contained in:
Andrew Tridgell 2021-03-14 09:56:43 +11:00
parent 4f10565f82
commit dda69bfcb0
3 changed files with 18 additions and 1 deletions

View File

@ -142,6 +142,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Group: OUT
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
GOBJECT(servo_channels, "OUT", SRV_Channels),
// PWM type for ESCs (to allow for DShot and OneShot)
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
#endif
#ifdef HAL_PERIPH_ENABLE_MSP

View File

@ -37,6 +37,7 @@ public:
k_param_gps_port,
k_param_msp_port,
k_param_notify,
k_param_esc_pwm_type,
};
AP_Int16 format_version;
@ -81,7 +82,11 @@ public:
#ifdef HAL_PERIPH_ENABLE_MSP
AP_Int8 msp_port;
#endif
#ifdef HAL_PERIPH_ENABLE_RC_OUT
AP_Int8 esc_pwm_type;
#endif
AP_Int8 debug;
AP_Int32 serial_number;

View File

@ -42,10 +42,19 @@ void AP_Periph_FW::rcout_init()
for (uint8_t i=0; i<SERVO_OUT_RCIN_MAX; i++) {
SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000);
}
uint16_t esc_mask = 0;
for (uint8_t i=0; i<SERVO_OUT_MOTOR_MAX; i++) {
SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), UAVCAN_ESC_MAX_VALUE);
uint8_t chan;
if (SRV_Channels::find_channel(SRV_Channels::get_motor_function(i), chan)) {
esc_mask |= 1U << chan;
}
}
// setup ESCs with the desired PWM type, allowing for DShot
hal.rcout->set_output_mode(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get());
// run this once and at 1Hz to configure aux and esc ranges
rcout_init_1Hz();
}