Browse Source

AP_Periph: added ESC_PWM_TYPE

this allows for oneshot and dshot on AP_Periph ESCs
c415-sdk
Andrew Tridgell 4 years ago
parent
commit
dda69bfcb0
  1. 3
      Tools/AP_Periph/Parameters.cpp
  2. 5
      Tools/AP_Periph/Parameters.h
  3. 9
      Tools/AP_Periph/rc_out.cpp

3
Tools/AP_Periph/Parameters.cpp

@ -142,6 +142,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Group: OUT // @Group: OUT
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp // @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
GOBJECT(servo_channels, "OUT", SRV_Channels), 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 #endif
#ifdef HAL_PERIPH_ENABLE_MSP #ifdef HAL_PERIPH_ENABLE_MSP

5
Tools/AP_Periph/Parameters.h

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

9
Tools/AP_Periph/rc_out.cpp

@ -42,10 +42,19 @@ void AP_Periph_FW::rcout_init()
for (uint8_t i=0; i<SERVO_OUT_RCIN_MAX; i++) { 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); 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++) { 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); 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 // run this once and at 1Hz to configure aux and esc ranges
rcout_init_1Hz(); rcout_init_1Hz();
} }

Loading…
Cancel
Save