Added new configuration parameter UAVCAN_ESC_IDLT.

This parameter, when enabled, enforces that the UAVCAN ESC driver never outputs zero throttle
while the system is armed. This feature is disabled by default, so the change will not break
the experience of current users.
This commit is contained in:
Pavel Kirienko
2016-08-06 14:47:50 +03:00
committed by Lorenz Meier
parent 2ba70c5d89
commit e27d3f4e13
4 changed files with 22 additions and 9 deletions

View File

@@ -660,6 +660,12 @@ int UavcanNode::init(uavcan::NodeID node_id)
return ret;
}
{
std::int32_t idle_throttle_when_armed = 0;
(void) param_get(param_find("UAVCAN_ESC_IDLT"), &idle_throttle_when_armed);
_esc_controller.enable_idle_throttle_when_armed(idle_throttle_when_armed > 0);
}
ret = _hardpoint_controller.init();
if (ret < 0) {