mirror of https://github.com/ArduPilot/ardupilot
AP_UAVCAN: support sending pulses as PWM for DroneCAN actuators
This commit is contained in:
parent
52ba9be204
commit
232c31053e
|
@ -528,11 +528,13 @@ void AP_UAVCAN::SRV_send_actuator(void)
|
|||
if (_SRV_conf[starting_servo].servo_pending && ((((uint32_t) 1) << starting_servo) & _servo_bm)) {
|
||||
cmd.actuator_id = starting_servo + 1;
|
||||
|
||||
// TODO: other types
|
||||
cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS;
|
||||
|
||||
// TODO: failsafe, safety
|
||||
cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0);
|
||||
if (option_is_set(Options::USE_ACTUATOR_PWM)) {
|
||||
cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_PWM;
|
||||
cmd.command_value = _SRV_conf[starting_servo].pulse;
|
||||
} else {
|
||||
cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS;
|
||||
cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0);
|
||||
}
|
||||
|
||||
msg.commands.push_back(cmd);
|
||||
|
||||
|
|
|
@ -203,6 +203,7 @@ public:
|
|||
DNA_IGNORE_DUPLICATE_NODE = (1U<<1),
|
||||
CANFD_ENABLED = (1U<<2),
|
||||
DNA_IGNORE_UNHEALTHY_NODE = (1U<<3),
|
||||
USE_ACTUATOR_PWM = (1U<<4),
|
||||
};
|
||||
|
||||
// check if a option is set
|
||||
|
|
Loading…
Reference in New Issue