PX4-Autopilot/msg/system_power.msg
David Sidrane f13682223a Added FMUv5 System Power related system_power.msg fields
voltage3V3_v - the sensor 3.3V voltage rail
   v3v3_valid   - the value of voltage3V3_v  may be 0. This
                  field is a 1 when the HW provides voltage3V3_v

   brick_valid - is now a bit mask. A 1 in the postion inticate the
                 Power controler HW has a valid supply voltage
                 present (in V window) on that priority
                 (channel V1..Vn).
                 The mapping is formed by 1<<battery_status.msg.priority
                 or using the manifest constanst BRICKn_VALID_MASK

   usb_vaild - is now indicated from the Power controler HW or
               the usb_connected if Power controler is
               not present.

   brick_valid == 0 and usb_vaild = 1 implies the FMU is powered
   from USB only

   brick_valid != 0  and usb_vaild = 1 implies the FMU is powered
   from the higest priority brick, providing a 1 bit in brick_valid
   and from USB
2017-07-17 21:02:50 -10:00

18 lines
673 B
Plaintext

float32 voltage5V_v # peripheral 5V rail voltage
float32 voltage3V3_v # Sensor 3V3 rail voltage
uint8 v3v3_valid # Sensor 3V3 rail voltage was read.
uint8 usb_connected # USB is connected when 1
uint8 brick_valid # brick bits power is good when bit 1
uint8 usb_vaild # USB is valid when 1
uint8 servo_valid # servo power is good when 1
uint8 periph_5V_OC # peripheral overcurrent when 1
uint8 hipower_5V_OC # hi power peripheral overcurrent when 1
uint8 BRICK1_VALID_SHIFTS=0
uint8 BRICK1_VALID_MASK=1
uint8 BRICK2_VALID_SHIFTS=1
uint8 BRICK2_VALID_MASK=2
uint8 BRICK3_VALID_SHIFTS=2
uint8 BRICK3_VALID_MASK=4
uint8 BRICK4_VALID_SHIFTS=3
uint8 BRICK4_VALID_MASK=8