List of common States and Corresponding ROS Parameters and Topics

CommonCommonStateAllStatesChanged
State sent when all product states has been sent.
CommonCommonStateBatteryStateChanged
Battery state
CommonCommonStateMassStorageStateListChanged
Mass storage state list
CommonCommonStateMassStorageInfoStateListChanged
Mass storage info state list
CommonCommonStateCurrentDateChanged
Current date state
CommonCommonStateCurrentTimeChanged
Current time state
CommonCommonStateMassStorageInfoRemainingListChanged
@deprecated Mass storage info remaining list
CommonCommonStateWifiSignalChanged
Wifi Signal between controller and product state
CommonCommonStateSensorsStatesListChanged
Sensors states list
CommonCommonStateProductModel
Inform of the product model. This is used to customize the UI depending on the connected product.
CommonCommonStateCountryListKnown
List of the countries known by the device
CommonOverHeatStateOverHeatChanged
@deprecated Overheat temperature reached
CommonOverHeatStateOverHeatRegulationChanged
@deprecated Overheat regulation state changed
CommonMavlinkStateMavlinkFilePlayingStateChanged
Playing state of a mavlink flight plan
CommonMavlinkStateMavlinkPlayErrorStateChanged
FlightPlan play state error
CommonCalibrationStateMagnetoCalibrationStateChanged
Sent when the state of the magneto calibration has changed
CommonCalibrationStateMagnetoCalibrationRequiredState
Status of the calibration requirement
CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged
Event sent by a product to inform about the axis to calibrate
CommonCalibrationStateMagnetoCalibrationStartedChanged
Status of the calibration process
CommonFlightPlanStateAvailabilityStateChanged
State of availability to run a flight plan file
CommonFlightPlanStateComponentStateListChanged
List of state of drone flightPlan components
CommonARLibsVersionsStateControllerLibARCommandsVersion
Controller libARCommands version
CommonARLibsVersionsStateSkyControllerLibARCommandsVersion
SkyController libARCommands version
CommonARLibsVersionsStateDeviceLibARCommandsVersion
Device libARCommands version
CommonAudioStateAudioStreamingRunning
Notify the controller whether the audio streaming is running.
CommonHeadlightsStateintensityChanged
Notify the instensity values for headlight LEDs.
CommonAnimationsStateList
List of animations state.
CommonAccessoryStateSupportedAccessoriesListChanged
List of supported accessories
CommonAccessoryStateAccessoryConfigChanged
Accessory config response.
CommonAccessoryStateAccessoryConfigModificationEnabled
Possibility to modify the accessory configuration.
CommonChargerStateMaxChargeRateChanged
@deprecated The maximum charge rate reported by the firmware.
CommonChargerStateCurrentChargeStateChanged
@deprecated The charge status of the battery changed.
CommonChargerStateLastChargeRateChanged
@deprecated The charge rate of the last charge sent by the firmware.
CommonChargerStateChargingInfo
Information of the charge.
CommonRunStateRunIdChanged
Sent when a run id has changed Run ids are uniquely identifying a run or a flight

CommonCommonStateAllStatesChanged

State sent when all product states has been sent.

  • Parameter: ~states/enable_commonstate_allstateschanged
  • Topic: states/common/CommonState/AllStatesChanged
  • Message type: bebop_msgs::CommonCommonStateAllStatesChanged
CommonCommonStateAllStatesChanged.msg

Header header

CommonCommonStateBatteryStateChanged

Battery state

  • Parameter: ~states/enable_commonstate_batterystatechanged
  • Topic: states/common/CommonState/BatteryStateChanged
  • Message type: bebop_msgs::CommonCommonStateBatteryStateChanged
CommonCommonStateBatteryStateChanged.msg

Header header

# Battery percentage
uint8 percent

CommonCommonStateMassStorageStateListChanged

Mass storage state list

  • Parameter: ~states/enable_commonstate_massstoragestatelistchanged
  • Topic: states/common/CommonState/MassStorageStateListChanged
  • Message type: bebop_msgs::CommonCommonStateMassStorageStateListChanged
CommonCommonStateMassStorageStateListChanged.msg

Header header

# Mass storage id (unique)
uint8 mass_storage_id
# Mass storage name
string name

CommonCommonStateMassStorageInfoStateListChanged

Mass storage info state list

  • Parameter: ~states/enable_commonstate_massstorageinfostatelistchanged
  • Topic: states/common/CommonState/MassStorageInfoStateListChanged
  • Message type: bebop_msgs::CommonCommonStateMassStorageInfoStateListChanged
CommonCommonStateMassStorageInfoStateListChanged.msg

Header header

# Mass storage state id (unique)
uint8 mass_storage_id
# Mass storage size in MBytes
uint32 size
# Mass storage used size in MBytes
uint32 used_size
# Mass storage plugged (1 if mass storage is plugged, otherwise 0)
uint8 plugged
# Mass storage full information state (1 if mass storage full, 0 otherwise).
uint8 full
# Mass storage internal type state (1 if mass storage is internal, 0 otherwise)
uint8 internal

CommonCommonStateCurrentDateChanged

Current date state

  • Parameter: ~states/enable_commonstate_currentdatechanged
  • Topic: states/common/CommonState/CurrentDateChanged
  • Message type: bebop_msgs::CommonCommonStateCurrentDateChanged
CommonCommonStateCurrentDateChanged.msg

Header header

# Date with ISO-8601 format
string date

CommonCommonStateCurrentTimeChanged

Current time state

  • Parameter: ~states/enable_commonstate_currenttimechanged
  • Topic: states/common/CommonState/CurrentTimeChanged
  • Message type: bebop_msgs::CommonCommonStateCurrentTimeChanged
CommonCommonStateCurrentTimeChanged.msg

Header header

# Time with ISO-8601 format
string time

CommonCommonStateMassStorageInfoRemainingListChanged

@deprecated Mass storage info remaining list

  • Parameter: ~states/enable_commonstate_massstorageinforemaininglistchanged
  • Topic: states/common/CommonState/MassStorageInfoRemainingListChanged
  • Message type: bebop_msgs::CommonCommonStateMassStorageInfoRemainingListChanged
CommonCommonStateMassStorageInfoRemainingListChanged.msg

Header header

# Mass storage free space in MBytes
uint32 free_space
# Mass storage record time reamining in minute
uint16 rec_time
# Mass storage photo remaining
uint32 photo_remaining

CommonCommonStateWifiSignalChanged

Wifi Signal between controller and product state

  • Parameter: ~states/enable_commonstate_wifisignalchanged
  • Topic: states/common/CommonState/WifiSignalChanged
  • Message type: bebop_msgs::CommonCommonStateWifiSignalChanged
CommonCommonStateWifiSignalChanged.msg

Header header

# RSSI of the signal between controller and the product (in dbm)
int16 rssi

CommonCommonStateSensorsStatesListChanged

Sensors states list

  • Parameter: ~states/enable_commonstate_sensorsstateslistchanged
  • Topic: states/common/CommonState/SensorsStatesListChanged
  • Message type: bebop_msgs::CommonCommonStateSensorsStatesListChanged
CommonCommonStateSensorsStatesListChanged.msg

Header header

# Sensor name
uint8 sensorName_IMU=0  # Inertial Measurement Unit sensor
uint8 sensorName_barometer=1  # Barometer sensor
uint8 sensorName_ultrasound=2  # Ultrasonic sensor
uint8 sensorName_GPS=3  # GPS sensor
uint8 sensorName_magnetometer=4  # Magnetometer sensor
uint8 sensorName_vertical_camera=5  # Vertical Camera sensor
uint8 sensorName
# Sensor state (1 if the sensor is OK, 0 if the sensor is NOT OK)
uint8 sensorState

CommonCommonStateProductModel

Inform of the product model. This is used to customize the UI depending on the connected product.

  • Parameter: ~states/enable_commonstate_productmodel
  • Topic: states/common/CommonState/ProductModel
  • Message type: bebop_msgs::CommonCommonStateProductModel
CommonCommonStateProductModel.msg

Header header

# The Model of the product.
uint8 model_RS_TRAVIS=0  # Travis (RS taxi) model.
uint8 model_RS_MARS=1  # Mars (RS space) model
uint8 model_RS_SWAT=2  # SWAT (RS SWAT) model
uint8 model_RS_MCLANE=3  # Mc Lane (RS police) model
uint8 model_RS_BLAZE=4  # Blaze (RS fire) model
uint8 model_RS_ORAK=5  # Orak (RS carbon hydrofoil) model
uint8 model_RS_NEWZ=6  # New Z (RS wooden hydrofoil) model
uint8 model_JS_MARSHALL=7  # Marshall (JS fire) model
uint8 model_JS_DIESEL=8  # Diesel (JS SWAT) model
uint8 model_JS_BUZZ=9  # Buzz (JS space) model
uint8 model_JS_MAX=10  # Max (JS F1) model
uint8 model_JS_JETT=11  # Jett (JS flames) model
uint8 model_JS_TUKTUK=12  # Tuk-Tuk (JS taxi) model
uint8 model

CommonCommonStateCountryListKnown

List of the countries known by the device

  • Parameter: ~states/enable_commonstate_countrylistknown
  • Topic: states/common/CommonState/CountryListKnown
  • Message type: bebop_msgs::CommonCommonStateCountryListKnown
CommonCommonStateCountryListKnown.msg

Header header

# List entry attribute Bitfield. 0x01: First: indicate its the first element of the list. 0x02: Last: indicate its the last element of the list. 0x04: Empty: indicate the list is empty (implies First/Last). All other arguments should be ignored.
uint8 listFlags
# Following of country code with ISO 3166 format, separated by ;. Be careful of the command size allowed by the network used. If necessary, split the list in several commands.
string countryCodes

CommonOverHeatStateOverHeatChanged

@deprecated Overheat temperature reached

  • Parameter: ~states/enable_overheatstate_overheatchanged
  • Topic: states/common/OverHeatState/OverHeatChanged
  • Message type: bebop_msgs::CommonOverHeatStateOverHeatChanged
CommonOverHeatStateOverHeatChanged.msg

Header header

CommonOverHeatStateOverHeatRegulationChanged

@deprecated Overheat regulation state changed

  • Parameter: ~states/enable_overheatstate_overheatregulationchanged
  • Topic: states/common/OverHeatState/OverHeatRegulationChanged
  • Message type: bebop_msgs::CommonOverHeatStateOverHeatRegulationChanged
CommonOverHeatStateOverHeatRegulationChanged.msg

Header header

# Type of overheat regulation : 0 for ventilation, 1 for switch off
uint8 regulationType

CommonMavlinkStateMavlinkFilePlayingStateChanged

Playing state of a mavlink flight plan

  • Parameter: ~states/enable_mavlinkstate_mavlinkfileplayingstatechanged
  • Topic: states/common/MavlinkState/MavlinkFilePlayingStateChanged
  • Message type: bebop_msgs::CommonMavlinkStateMavlinkFilePlayingStateChanged
CommonMavlinkStateMavlinkFilePlayingStateChanged.msg

Header header

# State of the mavlink
uint8 state_playing=0  # Mavlink file is playing
uint8 state_stopped=1  # Mavlink file is stopped (arg filepath and type are useless in this state)
uint8 state_paused=2  # Mavlink file is paused
uint8 state
# flight plan file path from the mavlink ftp root
string filepath
# type of the played mavlink file
uint8 type_flightPlan=0  # Mavlink file for FlightPlan
uint8 type_mapMyHouse=1  # Mavlink file for MapMyHouse
uint8 type

CommonMavlinkStateMavlinkPlayErrorStateChanged

FlightPlan play state error

  • Parameter: ~states/enable_mavlinkstate_mavlinkplayerrorstatechanged
  • Topic: states/common/MavlinkState/MavlinkPlayErrorStateChanged
  • Message type: bebop_msgs::CommonMavlinkStateMavlinkPlayErrorStateChanged
CommonMavlinkStateMavlinkPlayErrorStateChanged.msg

Header header

# State of play error
uint8 error_none=0  # There is no error
uint8 error_notInOutDoorMode=1  # The drone is not in outdoor mode
uint8 error_gpsNotFixed=2  # The gps is not fixed
uint8 error_notCalibrated=3  # The magnetometer of the drone is not calibrated
uint8 error

CommonCalibrationStateMagnetoCalibrationStateChanged

Sent when the state of the magneto calibration has changed

  • Parameter: ~states/enable_calibrationstate_magnetocalibrationstatechanged
  • Topic: states/common/CalibrationState/MagnetoCalibrationStateChanged
  • Message type: bebop_msgs::CommonCalibrationStateMagnetoCalibrationStateChanged
CommonCalibrationStateMagnetoCalibrationStateChanged.msg

Header header

# State of the x axis (roll) calibration : 1 if calibration is done, 0 otherwise
uint8 xAxisCalibration
# State of the y axis (pitch) calibration : 1 if calibration is done, 0 otherwise
uint8 yAxisCalibration
# State of the z axis (yaw) calibration : 1 if calibration is done, 0 otherwise
uint8 zAxisCalibration
# 1 if calibration has failed, 0 otherwise. If this arg is 1, consider all previous arg as 0
uint8 calibrationFailed

CommonCalibrationStateMagnetoCalibrationRequiredState

Status of the calibration requirement

  • Parameter: ~states/enable_calibrationstate_magnetocalibrationrequiredstate
  • Topic: states/common/CalibrationState/MagnetoCalibrationRequiredState
  • Message type: bebop_msgs::CommonCalibrationStateMagnetoCalibrationRequiredState
CommonCalibrationStateMagnetoCalibrationRequiredState.msg

Header header

# 1 if calibration is required, 0 if current calibration is still valid
uint8 required

CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged

Event sent by a product to inform about the axis to calibrate

  • Parameter: ~states/enable_calibrationstate_magnetocalibrationaxistocalibratechanged
  • Topic: states/common/CalibrationState/MagnetoCalibrationAxisToCalibrateChanged
  • Message type: bebop_msgs::CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged
CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged.msg

Header header

# The axis to calibrate
uint8 axis_xAxis=0  # If the current calibration axis should be the x axis
uint8 axis_yAxis=1  # If the current calibration axis should be the y axis
uint8 axis_zAxis=2  # If the current calibration axis should be the z axis
uint8 axis_none=3  # If none of the axis should be calibrated
uint8 axis

CommonCalibrationStateMagnetoCalibrationStartedChanged

Status of the calibration process

  • Parameter: ~states/enable_calibrationstate_magnetocalibrationstartedchanged
  • Topic: states/common/CalibrationState/MagnetoCalibrationStartedChanged
  • Message type: bebop_msgs::CommonCalibrationStateMagnetoCalibrationStartedChanged
CommonCalibrationStateMagnetoCalibrationStartedChanged.msg

Header header

# 1 if calibration has started, 0 otherwise
uint8 started

CommonFlightPlanStateAvailabilityStateChanged

State of availability to run a flight plan file

  • Parameter: ~states/enable_flightplanstate_availabilitystatechanged
  • Topic: states/common/FlightPlanState/AvailabilityStateChanged
  • Message type: bebop_msgs::CommonFlightPlanStateAvailabilityStateChanged
CommonFlightPlanStateAvailabilityStateChanged.msg

Header header

# Running a flightPlan file is available (1 running a flightPlan file is available, otherwise 0)
uint8 AvailabilityState

CommonFlightPlanStateComponentStateListChanged

List of state of drone flightPlan components

  • Parameter: ~states/enable_flightplanstate_componentstatelistchanged
  • Topic: states/common/FlightPlanState/ComponentStateListChanged
  • Message type: bebop_msgs::CommonFlightPlanStateComponentStateListChanged
CommonFlightPlanStateComponentStateListChanged.msg

Header header

# Drone FlightPlan component id (unique)
uint8 component_GPS=0  # GPS for Drone FlightPlan
uint8 component_Calibration=1  # Calibration for Drone FlightPlan
uint8 component_Mavlink_File=2  # Mavlink file for Drone FlightPlan
uint8 component_TakeOff=3  # Take off
uint8 component
# State of the FlightPlan component (1 FlightPlan component OK, otherwise 0)
uint8 State

CommonARLibsVersionsStateControllerLibARCommandsVersion

Controller libARCommands version

  • Parameter: ~states/enable_arlibsversionsstate_controllerlibarcommandsversion
  • Topic: states/common/ARLibsVersionsState/ControllerLibARCommandsVersion
  • Message type: bebop_msgs::CommonARLibsVersionsStateControllerLibARCommandsVersion
CommonARLibsVersionsStateControllerLibARCommandsVersion.msg

Header header

# version of libARCommands (1.2.3.4 format)
string version

CommonARLibsVersionsStateSkyControllerLibARCommandsVersion

SkyController libARCommands version

  • Parameter: ~states/enable_arlibsversionsstate_skycontrollerlibarcommandsversion
  • Topic: states/common/ARLibsVersionsState/SkyControllerLibARCommandsVersion
  • Message type: bebop_msgs::CommonARLibsVersionsStateSkyControllerLibARCommandsVersion
CommonARLibsVersionsStateSkyControllerLibARCommandsVersion.msg

Header header

# version of libARCommands (1.2.3.4 format)
string version

CommonARLibsVersionsStateDeviceLibARCommandsVersion

Device libARCommands version

  • Parameter: ~states/enable_arlibsversionsstate_devicelibarcommandsversion
  • Topic: states/common/ARLibsVersionsState/DeviceLibARCommandsVersion
  • Message type: bebop_msgs::CommonARLibsVersionsStateDeviceLibARCommandsVersion
CommonARLibsVersionsStateDeviceLibARCommandsVersion.msg

Header header

# version of libARCommands (1.2.3.4 format)
string version

CommonAudioStateAudioStreamingRunning

Notify the controller whether the audio streaming is running.

  • Parameter: ~states/enable_audiostate_audiostreamingrunning
  • Topic: states/common/AudioState/AudioStreamingRunning
  • Message type: bebop_msgs::CommonAudioStateAudioStreamingRunning
CommonAudioStateAudioStreamingRunning.msg

Header header

# Bit field for TX and RX running bit 0 is 1 if Drone TX is running bit 1 is 1 if Drone RX is running
uint8 running

CommonHeadlightsStateintensityChanged

Notify the instensity values for headlight LEDs.

  • Parameter: ~states/enable_headlightsstate_intensitychanged
  • Topic: states/common/HeadlightsState/intensityChanged
  • Message type: bebop_msgs::CommonHeadlightsStateintensityChanged
CommonHeadlightsStateintensityChanged.msg

Header header

# The intensity value for the left LED (0 through 255).
uint8 left
# The intensity value for the right LED (0 through 255).
uint8 right

CommonAnimationsStateList

List of animations state.

  • Parameter: ~states/enable_animationsstate_list
  • Topic: states/common/AnimationsState/List
  • Message type: bebop_msgs::CommonAnimationsStateList
CommonAnimationsStateList.msg

Header header

# Animation type.
uint8 anim_HEADLIGHTS_FLASH=0  # Flash headlights.
uint8 anim_HEADLIGHTS_BLINK=1  # Blink headlights.
uint8 anim_HEADLIGHTS_OSCILLATION=2  # Oscillating headlights.
uint8 anim_SPIN=3  # Spin animation.
uint8 anim_TAP=4  # Tap animation.
uint8 anim_SLOW_SHAKE=5  # Slow shake animation.
uint8 anim_METRONOME=6  # Metronome animation.
uint8 anim_ONDULATION=7  # Standing dance animation.
uint8 anim_SPIN_JUMP=8  # Spin jump animation.
uint8 anim_SPIN_TO_POSTURE=9  # Spin that end in standing posture, or in jumper if it was standing animation.
uint8 anim_SPIRAL=10  # Spiral animation.
uint8 anim_SLALOM=11  # Slalom animation.
uint8 anim_BOOST=12  # Boost animation.
uint8 anim
# State of the animation
uint8 state_stopped=0  # animation is stopped
uint8 state_started=1  # animation is started
uint8 state_notAvailable=2  # The animation is not available
uint8 state
# Error to explain the state
uint8 error_ok=0  # No Error
uint8 error_unknown=1  # Unknown generic error
uint8 error

CommonAccessoryStateSupportedAccessoriesListChanged

List of supported accessories

  • Parameter: ~states/enable_accessorystate_supportedaccessorieslistchanged
  • Topic: states/common/AccessoryState/SupportedAccessoriesListChanged
  • Message type: bebop_msgs::CommonAccessoryStateSupportedAccessoriesListChanged
CommonAccessoryStateSupportedAccessoriesListChanged.msg

Header header

# Accessory configurations supported by the product.
uint8 accessory_NO_ACCESSORY=0  # No accessory.
uint8 accessory_STD_WHEELS=1  # Standard wheels
uint8 accessory_TRUCK_WHEELS=2  # Truck wheels
uint8 accessory_HULL=3  # Hull
uint8 accessory_HYDROFOIL=4  # Hydrofoil
uint8 accessory

CommonAccessoryStateAccessoryConfigChanged

Accessory config response.

  • Parameter: ~states/enable_accessorystate_accessoryconfigchanged
  • Topic: states/common/AccessoryState/AccessoryConfigChanged
  • Message type: bebop_msgs::CommonAccessoryStateAccessoryConfigChanged
CommonAccessoryStateAccessoryConfigChanged.msg

Header header

# Accessory configuration reported by firmware.
uint8 newAccessory_UNCONFIGURED=0  # No accessory configuration set. Controller needs to set one.
uint8 newAccessory_NO_ACCESSORY=1  # No accessory.
uint8 newAccessory_STD_WHEELS=2  # Standard wheels
uint8 newAccessory_TRUCK_WHEELS=3  # Truck wheels
uint8 newAccessory_HULL=4  # Hull
uint8 newAccessory_HYDROFOIL=5  # Hydrofoil
uint8 newAccessory
# Error code.
uint8 error_OK=0  # No error. Accessory config change successful.
uint8 error_UNKNOWN=1  # Cannot change accessory configuration for some reason.
uint8 error_FLYING=2  # Cannot change accessory configuration while flying.
uint8 error

CommonAccessoryStateAccessoryConfigModificationEnabled

Possibility to modify the accessory configuration.

  • Parameter: ~states/enable_accessorystate_accessoryconfigmodificationenabled
  • Topic: states/common/AccessoryState/AccessoryConfigModificationEnabled
  • Message type: bebop_msgs::CommonAccessoryStateAccessoryConfigModificationEnabled
CommonAccessoryStateAccessoryConfigModificationEnabled.msg

Header header

# 1 if the modification of the accessory Config is enabled, 0 otherwise
uint8 enabled

CommonChargerStateMaxChargeRateChanged

@deprecated The maximum charge rate reported by the firmware.

  • Parameter: ~states/enable_chargerstate_maxchargeratechanged
  • Topic: states/common/ChargerState/MaxChargeRateChanged
  • Message type: bebop_msgs::CommonChargerStateMaxChargeRateChanged
CommonChargerStateMaxChargeRateChanged.msg

Header header

# The current maximum charge rate.
uint8 rate_SLOW=0  # Fully charge the battery at a slow rate. Typically limit max charge current to 512 mA.
uint8 rate_MODERATE=1  # Almost fully-charge the battery at moderate rate (> 512 mA) but slower than the fastest rate.
uint8 rate_FAST=2  # Almost fully-charge the battery at the highest possible rate supported by the charger.
uint8 rate

CommonChargerStateCurrentChargeStateChanged

@deprecated The charge status of the battery changed.

  • Parameter: ~states/enable_chargerstate_currentchargestatechanged
  • Topic: states/common/ChargerState/CurrentChargeStateChanged
  • Message type: bebop_msgs::CommonChargerStateCurrentChargeStateChanged
CommonChargerStateCurrentChargeStateChanged.msg

Header header

# Charger status.
uint8 status_DISCHARGING=0  # The battery is discharging.
uint8 status_CHARGING_SLOW=1  # The battery is charging at a slow rate about 512 mA.
uint8 status_CHARGING_MODERATE=2  # The battery is charging at a moderate rate (> 512 mA) but slower than the fastest rate.
uint8 status_CHARGING_FAST=3  # The battery is charging at a the fastest rate.
uint8 status_BATTERY_FULL=4  # The charger is plugged and the battery is fully charged.
uint8 status
# The current charging phase.
uint8 phase_UNKNOWN=0  # The charge phase is unknown or irrelevant.
uint8 phase_CONSTANT_CURRENT_1=1  # First phase of the charging process. The battery is charging with constant current.
uint8 phase_CONSTANT_CURRENT_2=2  # Second phase of the charging process. The battery is charging with constant current, with a higher voltage than the first phase.
uint8 phase_CONSTANT_VOLTAGE=3  # Last part of the charging process. The battery is charging with a constant voltage.
uint8 phase_CHARGED=4  # The battery is fully charged.
uint8 phase

CommonChargerStateLastChargeRateChanged

@deprecated The charge rate of the last charge sent by the firmware.

  • Parameter: ~states/enable_chargerstate_lastchargeratechanged
  • Topic: states/common/ChargerState/LastChargeRateChanged
  • Message type: bebop_msgs::CommonChargerStateLastChargeRateChanged
CommonChargerStateLastChargeRateChanged.msg

Header header

# The charge rate recorded by the firmware for the last charge.
uint8 rate_UNKNOWN=0  # The last charge rate is not known.
uint8 rate_SLOW=1  # Slow charge rate.
uint8 rate_MODERATE=2  # Moderate charge rate.
uint8 rate_FAST=3  # Fast charge rate.
uint8 rate

CommonChargerStateChargingInfo

Information of the charge.

  • Parameter: ~states/enable_chargerstate_charginginfo
  • Topic: states/common/ChargerState/ChargingInfo
  • Message type: bebop_msgs::CommonChargerStateChargingInfo
CommonChargerStateChargingInfo.msg

Header header

# The current charging phase.
uint8 phase_UNKNOWN=0  # The charge phase is unknown or irrelevant.
uint8 phase_CONSTANT_CURRENT_1=1  # First phase of the charging process. The battery is charging with constant current.
uint8 phase_CONSTANT_CURRENT_2=2  # Second phase of the charging process. The battery is charging with constant current, with a higher voltage than the first phase.
uint8 phase_CONSTANT_VOLTAGE=3  # Last part of the charging process. The battery is charging with a constant voltage.
uint8 phase_CHARGED=4  # The battery is fully charged.
uint8 phase_DISCHARGING=5  # The battery is discharging; Other arguments refers to the last charge.
uint8 phase
# The charge rate. If phase is DISCHARGING, refers to the last charge.
uint8 rate_UNKNOWN=0  # The charge rate is not known.
uint8 rate_SLOW=1  # Slow charge rate.
uint8 rate_MODERATE=2  # Moderate charge rate.
uint8 rate_FAST=3  # Fast charge rate.
uint8 rate
# The charging intensity, in dA. (12dA = 1,2A) ; If phase is DISCHARGING, refers to the last charge. Equals to 0 if not known.
uint8 intensity
# The full charging time estimated, in minute. If phase is DISCHARGING, refers to the last charge. Equals to 0 if not known.
uint8 fullChargingTime

CommonRunStateRunIdChanged

Sent when a run id has changed Run ids are uniquely identifying a run or a flight

  • Parameter: ~states/enable_runstate_runidchanged
  • Topic: states/common/RunState/RunIdChanged
  • Message type: bebop_msgs::CommonRunStateRunIdChanged
CommonRunStateRunIdChanged.msg

Header header

# Id of the run
string runId