this allows for an offset in ESC numbering for much more efficient CAN
bandwidth usage.
For example, on a coaxial OctoQuad quadplane the ESCs are typically
setup as outputs 5 to 12. An ideal setup is to split these over 2 CAN
buses, with one CAN bus for the top layer and the one bus for the
bottom layer (allowing for VTOL flight with one bus failed).
Without this offset parameter you would be sending RawCommand messages
like this:
bus1: [ 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
bus2: [ 0, 0, 0, 0, 0, 0, 0, 0, ESC1, ESC2, ESC3, ESC4 ]
this is very wasteful of bus bandwidth, with bus1 using 3x the
bandwidth it should and bus2 using 4x the bandwidth it should (the
above will take 3 can frames for bus1, and 4 can frames for bus 2)
With this patch you can set:
CAN_D1_UC_ESC_OF = 4
CAN_D2_UC_ESC_OF = 8
and you will get this on the bus:
bus1: [ ESC1, ESC2, ESC3, ESC4 ]
bus2: [ ESC1, ESC2, ESC3, ESC4 ]
that takes just 1 can frame per send on each bus
this allows for 2 ways of controlling conflicts in the UAVCAN DNA
database. The first is to set CAN_Dn_UC_OPTION to 1, which resets the
DNA database, thus clearing any node conflicts.
The second is to set CAN_Dn_UC_OPTION to 2, which ignores node
conflicts in the DNA database
These options are useful for vehicles with UAVCAN smart batteries
where the node ID is fixed but the hwid changes and you want to do
battery swapping (possibly without rebooting)
remove send_esc_telemetry_mavlink()
remove datastructures and semaphore obsoleted by AP_ESC_Telem* (<amilcar.lucas@iav.de>)
record volts, amps and consumption as floats
This can be used to command multiple devices on the UAVCAN bus to
update their LEDs. This will come in handy for status outputs etc.
This utilizes equipment.indication.LightsCommand message.
This message is not so important and therefore we limit publishing
it to avoid bus overflow. The priority of the message is also low.
To do so, we make use of UAVCAN message MagneticFieldStrength2, which
has a field describing the sensor_id of the node which measurements were
sent, and if a node sends this message we register multiple
AP_Compass_UAVCAN backends for this node. The routing of the messages
between those backends is also implemented here.