mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_KDECAN: map ESC id to servo channel and passthrough pwm
Co-authored-by: Siddharth Purohit <siddharthbharatpurohit@gmail.com>
This commit is contained in:
parent
6c93039d84
commit
d2b8fce25a
@ -570,17 +570,10 @@ void AP_KDECAN::update()
|
||||
if (_rc_out_sem.take(1)) {
|
||||
for (uint8_t i = 0; i < KDECAN_MAX_NUM_ESCS; i++) {
|
||||
if ((_esc_present_bitmask & (1 << i)) == 0) {
|
||||
_scaled_output[i] = 0;
|
||||
continue;
|
||||
}
|
||||
|
||||
SRV_Channel::Aux_servo_function_t motor_function = SRV_Channels::get_motor_function(i);
|
||||
|
||||
if (SRV_Channels::function_assigned(motor_function)) {
|
||||
float norm_output = SRV_Channels::get_output_norm(motor_function);
|
||||
_scaled_output[i] = uint16_t((norm_output + 1.0f) / 2.0f * 2000.0f);
|
||||
} else {
|
||||
_scaled_output[i] = 0;
|
||||
}
|
||||
_scaled_output[i] = SRV_Channels::srv_channel(i)->get_output_pwm();
|
||||
}
|
||||
|
||||
_rc_out_sem.give();
|
||||
|
@ -104,7 +104,7 @@ private:
|
||||
|
||||
|
||||
union frame_id_t {
|
||||
struct {
|
||||
struct PACKED {
|
||||
uint8_t object_address;
|
||||
uint8_t destination_id;
|
||||
uint8_t source_id;
|
||||
|
Loading…
Reference in New Issue
Block a user