AP_Periph: support actuator type with PWM

this makes debugging much easier in CAN analyser
This commit is contained in:
Andrew Tridgell 2022-09-12 13:27:22 +10:00
parent 0732c30e53
commit 31cac4395f
3 changed files with 20 additions and 6 deletions

View File

@ -219,7 +219,8 @@ public:
void rcout_init();
void rcout_init_1Hz();
void rcout_esc(int16_t *rc, uint8_t num_channels);
void rcout_srv(const uint8_t actuator_id, const float command_value);
void rcout_srv_unitless(const uint8_t actuator_id, const float command_value);
void rcout_srv_PWM(const uint8_t actuator_id, const float command_value);
void rcout_update();
void rcout_handle_safety_state(uint8_t safety_state);
#endif

View File

@ -796,11 +796,14 @@ static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer)
}
for (uint8_t i=0; i < data_count; i++) {
if (data[i].command_type != UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS) {
// this is the only type we support
continue;
switch (data[i].command_type) {
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS:
periph.rcout_srv_unitless(data[i].actuator_id, data[i].command_value);
break;
case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM:
periph.rcout_srv_PWM(data[i].actuator_id, data[i].command_value);
break;
}
periph.rcout_srv(data[i].actuator_id, data[i].command_value);
}
}
#endif // HAL_PERIPH_ENABLE_RC_OUT

View File

@ -99,7 +99,7 @@ void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels)
rcout_has_new_data_to_update = true;
}
void AP_Periph_FW::rcout_srv(uint8_t actuator_id, const float command_value)
void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_value)
{
#if HAL_PWM_COUNT > 0
const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);
@ -109,6 +109,16 @@ void AP_Periph_FW::rcout_srv(uint8_t actuator_id, const float command_value)
#endif
}
void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value)
{
#if HAL_PWM_COUNT > 0
const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1);
SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5));
rcout_has_new_data_to_update = true;
#endif
}
void AP_Periph_FW::rcout_handle_safety_state(uint8_t safety_state)
{
if (safety_state == 255) {