Messages list#

Messages exchanged between the different processes: Flight Supervisor, Guidance, Drone Controller, Services and the Mission UI.

There are two types of messages, commands and events.

Flight supervisor#

Flight supervisor contains the state machine of the autopilot. It receives commands from and sends events to the Mission UI.

External commands#

command emergency()#

Emergency command, the default behavior is to cut the motors (causing a freefall).

command flightplan_start(start_wpt_idx, waypoints)#

Start a FlightPlan based on a waypoints list.

Parameters:
  • start_wpt_idx (uint32) - Index of first waypoint.

  • waypoints - Array of waypoints.

command flightplan_abort()#

Abort the FlightPlan in progress.

command flightplan_pause()#

Pause a FlightPlan in progress. To resume a FlightPlan, see flightplan_resume().

command flightplan_resume()#

Resume a FlightPlan on pause.

command hand_land()#

Ask the drone to initiate hand landing.

command hand_takeoff()#

Prepare the drone for a hand take-off by starting the motors at a low rpm.

command hand_takeoff_abort()#

Abort current hand take-off.

command land()#

Land.

command lookat_start()#

Start to LookAt. The drone looks at the selected target.

command lookat_abort()#

Abort LookAt.

command move_to(latitude, longitude, altitude, heading)#
Parameters:
  • latitude (float64) - Latitude of the location to reach (°).

  • longitude (float64) - Longitude of the location to reach (°).

  • altitude (float64) - Altitude above take off point to reach (m).

  • heading (float32) - Heading, relative to the North (°).

command poi_start(latitude, longitude, altitude, mode)#

Start a piloted Point Of Interest (POI). During a piloted POI, the front camera always points towards the given POI. If mode is locked, the front camera pitch will track the POI altitude. If mode is free the user has control of the front camera pitch angle.

Parameters:
  • latitude (float64) - Latitude of the location to look at (°).

  • longitude (float64) - Longitude of the location to look at (°).

  • altitude (float64) - Altitude above take off to look at (m).

  • mode (enum.PoiType).

command poi_abort()#

Abort the piloted Point Of Interest (POI).

command relative_move_start(dx, dy, dz, dpsi)#

Move the drone relative to the current position and current heading angle.

Parameters:
  • dx (float32) - Wanted displacement along the front axis (m).

  • dy (float32) - Wanted displacement along the right axis (m).

  • dz (float32) - Wanted displacement along the down axis (m).

  • dpsi (float32) - Wanted rotation of heading (rad).

command smart_takeoff_land()#

Acts as a Takeoff or a Land command depending on the current drone state. This is used by controllers with a single takeoff/land button.

command takeoff()#

Ask the drone to take off.

External events#

This is a list of events sent by Flight Supervisor, matching the above commands.

event flightplan_state(state, evt, cause)#

State of the FlightPlan.

Parameters:
  • state (enum.FlightplanState) - FlightPlan state.

  • evt (enum.FlightplanEvt) - Flightplan event sent after a state change.

  • cause (:cpp:enum`enum.FlightplanReason<FlightplanReason>`) - Flightplan reason for a state change.

event flightplan_waypoint_evt(event, num)#

A waypoint has been reached or skipped.

Parameters:
event hand_land_state(evt)#

Sent when the drone is landing on a hand.

Parameter:

evt (enum.HandLandEvt).

event hand_takeoff_ready()#

Sent when the drone is ready to be hand launched after motors have started.

event lookat_state(behavior)#

LookAt state behavior.

Parameter:

behavior (enum.LookAtBehavior).

event move_to_status(latitude, longitude, altitude, heading, status)#

The drone moves or moved to a given location.

Parameters:
  • latitude (float64) - Latitude of the location to reach (°).

  • longitude (float64) - Longitude of the location to reach (°).

  • altitude (float64) - Altitude above take off point to reach (m).

  • heading (float32) - Heading, relative to the North (°).

  • status (enum.MoveStatus) - Status of the move_to().

event poi_changed(latitude, longitude, altitude, mode, status)#

Piloted POI state. Latitude, longitude, altitude and mode information are only valid when the status are pending or running.

Parameters:
  • latitude (float64) - Latitude of the location to look at (°).

  • longitude (float64) - Longitude of the location to look at (°).

  • altitude (float64) - Altitude above take-off point to look at (m).

  • mode (enum.PoiType) - POI mode.

  • status (enum.PoiStatus) - Status of the piloted POI.

event relative_move_status(dx, dy, dz, dpsi, status)#

Relative move ended. Informs about the move that the drone managed to do.

Parameters:
  • dx (float32) - Distance traveled along the front axis (m).

  • dy (float32) - Distance traveled along the right axis (m).

  • dz (float32) - Distance traveled along the down axis (m).

  • dpsi (float32) - Applied angle on heading (rad).

  • status : (enum.MoveStatus) - Status of the relative move.

Internal events#

struct Event#

Public Members

TimeOut time_out#

Generic timeout message.

generated when timer configured with :py:class:fsup.genstate.State.set_timeout expire.

WakeUp wake_up#

Generic wake_up message.

generated when timer configured with :py:class:fsup.genstate.State.wakeup_after or

‘genstate.State.wakeup_periodically’ expire.

google::protobuf::Empty landing#

Trigger a landing.

google::protobuf::Empty landing_interrupt_done#

Sent when a landing interruption is complete.

google::protobuf::Empty defective_barometer#

Sent when the barometer sensor is defective.

google::protobuf::Empty emergency_ground_reset#

Sent during emergency ground when all sensors are OK. Used to reset emergency state.

PcmdHoriz pcmd_horizontal_move#

Ask the drone to move in the horizontal plane.

PcmdYaw pcmd_yaw#

Ask the drone to turn around its yaw axis.

PcmdVertical pcmd_vertical#

Ask the drone to move vertically.

google::protobuf::Empty pcmd_gotofix#

Ask the drone to brake and go to fixed point.

google::protobuf::Empty pcmd_horizontal_move_zero#

Piloting command on the horizontal axes (roll, pitch) with zero values.

google::protobuf::Empty pcmd_yaw_zero#

Piloting yaw command with zero values.

google::protobuf::Empty pcmd_vertical_zero#

Piloting vertical command with zero values.

PcmdHoriz pcmd_horizontal_move_long#

Long press in the horizontal plane.

PcmdYaw pcmd_yaw_long#

Long press around yaw.

PcmdVertical pcmd_vertical_long#

Long press vertically.

google::protobuf::Empty is_steady#

Sent when motion state is: steady.

google::protobuf::Empty is_moving#

Sent when motion state is: moving.

Structures#

struct TimeOut#

Public Members

string reason#

Reason of the timeout, given at configuration.

struct WakeUp#

Public Members

string reason#

Reason of the wake up, given at configuration.

struct PowerAlertBatteryLevel#

Public Members

::PowerAlerts::BatteryPowerLevel::Enum level#

Power level.

struct PowerAlertRthCapacity#

Public Members

::PowerAlerts::RthBatteryCapacity::Enum capacity#

RTH battery capacity.

struct PcmdHoriz#

Public Members

float roll#

Roll angle in rad. If positive the drone will fly to the right.

float pitch#

Pitch angle in rad. If positive the drone will fly forward.

struct PcmdYaw#

Public Members

float yaw#

Yaw rotation speed in rad/s. If positive the drone will turn clockwise.

struct PcmdVertical#

Public Members

float vertical#

Vertical speed in m/s. If positive, the drone will go down.

Enumerations#

namespace BatteryPowerLevel#

Enums

enum Enum#

Values:

enumerator SHUTDOWN#

Battery power is too low, battery will go into shutdown

enumerator CRITICAL#

Critical battery level: just enough to trigger a landing

enumerator LOW#

Low battery, a critical landing will soon be triggered

enumerator OK#

Nominal power level

enumerator UNKNOWN#

Unknown power level

namespace RthBatteryCapacity#

Enums

enum Enum#

Values:

enumerator OK#

Enough battery to return home.

enumerator WARNING#

Battery will soon be at the minimum capacity to do a RTH.

enumerator CRITICAL#

Just enough battery to do a RTH.

enumerator TOOLATE#

Not enough battery to return home.

enumerator UNKNOWN#

Unknown battery consumption for RTH.

enum FlightplanEvt#
FLIGHTPLAN_EVT_STARTED (0)

The flightplan has been started

FLIGHTPLAN_EVT_PAUSED (1)

The flightplan has been paused

FLIGHTPLAN_EVT_ABORTED (2)

The flightplan has been aborted

FLIGHTPLAN_EVT_DONE (3)

The flightplan is completed (all waypoints reached or skipped)

FLIGHTPLAN_EVT_ENABLED (4)

The flightplan is enabled

FLIGHTPLAN_EVT_DISABLED (5)

The flightplan is disabled

enum FlightplanReason#
FLIGHTPLAN_REASON_OK (0)

The flightplan is started, paused, aborted by a user command, or completed

FLIGHTPLAN_REASON_GPS (1)

If GPS fix is lost, the flightplan is paused if it was running and disabled if not. If GPS fix is recovered, the flightplan is enabled

FLIGHTPLAN_REASON_LANDING (16)

The running flightplan is paused because of a landing command

FLIGHTPLAN_REASON_BATTERY_LOW (64)

The flightplan is disabled because battery level is low

FLIGHTPLAN_REASON_USER_EMERGENCY (128)

The flightplan is aborted because of a user emergency command

enum FlightplanState#
FLIGHTPLAN_STATE_UNAVAILABLE (0)

The flightplan is unavailable

FLIGHTPLAN_STATE_AVAILABLE (1)

The flightplan is available

FLIGHTPLAN_STATE_RUNNING (2)

The flightplan is running

enum FlightplanWaypointEvt#
FLIGHTPLAN_WAYPOINT_EVT_SKIPPED (0)

The waypoint has been skipped due to obstacle avoidance for example

FLIGHTPLAN_WAYPOINT_EVT_REACHED (1)

The waypoint has been reached

enum HandLandEvt#
HAND_LAND_EVT_IDLE (0)

Hand land is idle

HAND_LAND_EVT_ONGOING (1)

Hand land is ongoing

enum LookAtBehavior#
LOOKAT_BEHAVIOR_IDLE (0)

Drone is not looking at the target

LOOKAT_BEHAVIOR_LOOKAT (1)

Look at the target

enum MoveStatus#
MOVE_STATUS_RUNNING (0)

The drone is actually flying to the given position

MOVE_STATUS_DONE (1)

The drone has reached the target

MOVE_STATUS_ABORTED (2)

The move_to() has been aborted, either by an abort command or when a disconnection occurs

MOVE_STATUS_ERROR (3)

The move_to() has not been finished or started because of an error

enum PoiType#
POI_TYPE_FREE (0)

Front camera axes are freely controllable

POI_TYPE_LOCKED (1)

Front camera axes are locked on the POI

enum PoiStatus#
POI_STATUS_UNAVAILABLE (0)

The piloted POI is not available

POI_STATUS_AVAILABLE (1)

The piloted POI is available

POI_STATUS_RUNNING (3)

The Piloted POI is running

Guidance#

address: unix:/tmp/guidance

Core#

Guidance#

Commands#
struct Command#

Public Members

ModeConfig set_mode#

Set guidance mode.

Pcmd set_pcmd#

Set piloting commands.

string load_mission#

Load mission guidance modes.

string unload_mission#

Unload mission guidance modes.

bool set_obstacle_avoidance#

Enable or disable obstacle avoidance.

bool set_geofence#

Enable or disable geofence.

GeofenceCenter set_geofence_center#

Set geofence center.

Events#
struct Event#

Public Members

ModeList init_ok#

Send a list of loaded modes after init.

ModeChanged mode_changed#

Acknowledgment of set_mode command.

Error error#

Error message returned by a guidance mode via guidance::Mode::setError.

bool high_trajectory_deviation#

Distance from nominal trajectory exceeds threshold.

google::protobuf::Empty gotofix_done#

Request to go to fixed point completed.

bool horizontal_geofence_reached#

Indicate if the drone has reached the geofence horizontal limit

bool vertical_geofence_reached#

Indicate if the drone has reached the geofence vertical limit

GeofenceCenter geofence_center_changed#

Indicate that the center of the geofence changed.

Structures#
struct Error#

Public Members

string message#

Error message for logs.

string mode#

Current mode.

struct GeofenceCenter#

Public Members

float latitude#

Latitude of geofence center in degrees (north).

float longitude#

Longitude of geofence center in degrees (east).

struct ModeList#

Public Members

string loaded_modes[]#

List of loaded mode names.

struct MissionStatus#

Public Members

string mission#

Mission uid.

ModeList modes#

List of loaded modes.

struct ModeChanged#

Public Members

bool ok#

Indicate if the mode was correctly changed after request.

string mode#

New mode name. Set to the current mode in case of failure.

bool obstacle_avoidance_available#

Indicate if new mode supports obstacle avoidance.

bool geofence_available#

Indicate if new mode supports geofence.

struct Pcmd#

Public Members

float roll#

Roll angle [rad]. If positive the drone will fly to the right.

float pitch#

Pitch angle [rad]. If positive the drone will fly forward.

float yaw#

Yaw angular rate [rad/s]. If positive the drone will turn clockwise.

float vertical#

Vertical speed [m/s]. If positive, the drone will go down.

bool gotofix#

Brake and go to fixed point.

uint32 seqnum#

Sequence number at the source (only 8 bits used so it wraps at 255 -> 0).

uint32 ts#

Timestamp (in ms) at the source (only 24 bits used).

struct ModeConfig#

Public Members

string mode#

Mode name.

google::protobuf::Any config#

Serialized config object specific to each mode.

::Guidance::AxesCamController::Messages::Config cam_config_override[]#

Override the camera axes configuration (if supported).

If multiple configurations are given for the same camera, they will be

merged.

AxesCamController#

Commands#
struct Command#

Public Members

Reset reset#

Reset camera axes reference.

Reference set_reference#

Set camera axes reference.

Config set_config#

Set camera axes configuration.

Events#
struct Event#

Public Members

Config config#

Camera axes configuration advertised after a mode change.

ReferenceStatus reference_status#

Camera axes reference status

Capabilities capabilities#

Camera axes capabilities advertised when a client connects.

Structures#
struct AxisConfig#

Axis configuration.

Public Members

bool locked#

Specify if axis reference will be used or discarded.

bool filtered#

Enable filtering to have a smoother movement.

float smoothness#

The filtering magnitude applied to the axis.

float max_vel#

The maximum velocity of the axis.

struct AxisReference#

Reference for a single axis.

Public Members

CamController::Messages::ControlMode::Enum ctrl_mode#

Control mode type.

CamController::Messages::FrameOfReference::Enum frame_of_ref#

Axis position and velocity frame of reference.

float position#

Axis position reference [rad].

float velocity#

Axis velocity reference [rad/s].

struct Capabilities#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

bool yaw_drivable#

Yaw axis drivable.

bool pitch_drivable#

Pitch axis drivable.

bool roll_drivable#

Roll axis drivable.

Bounds yaw_bounds#

Angle bounds for yaw axis.

Bounds pitch_bounds#

Angle bounds for pitch axis.

Bounds roll_bounds#

Angle bounds for roll axis.

struct Bounds#

Public Members

float min#

Min angle value [rad].

float max#

Max angle value [rad].

struct Config#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

::AxesCamController::Messages::Config config#

Camera axes configuration.

struct Config#

Axes configuration.

Public Members

CamController::Messages::AxisConfig yaw#

Yaw axis configuration.

CamController::Messages::AxisConfig pitch#

Pitch axis configuration.

CamController::Messages::AxisConfig roll#

Roll axis configuration.

struct Reference#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

::AxesCamController::Messages::Reference reference#

Camera axes references.

struct Reference#

Axes reference, consisting of one reference for each axis (yaw, pitch, roll).

Public Members

CamController::Messages::AxisReference yaw#

Yaw axis reference.

CamController::Messages::AxisReference pitch#

Pitch axis reference.

CamController::Messages::AxisReference roll#

Roll axis reference.

struct ReferenceStatus#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

::AxesCamController::Messages::ReferenceStatus status#

Camera axes status.

struct ReferenceStatus#

Axes reference status.

Public Members

CamController::Messages::ReferenceStatus::Enum yaw#

Yaw axis reference status.

CamController::Messages::ReferenceStatus::Enum pitch#

Pitch axis reference status.

CamController::Messages::ReferenceStatus::Enum roll#

Roll axis reference status.

struct Reset#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

ZoomCamController#

Commands#
struct Command#

Public Members

Reset reset#

Reset camera zoom level.

Zoom set_zoom#

Set camera zoom level.

Config set_config#

Set camera zoom configuration.

Events#
struct Event#

Public Members

Config config#

Camera zoom configuration advertised after a mode change.

Structures#
struct Config#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

::ZoomCamController::Messages::Config config#

Camera zoom configuration.

struct Config#

Zoom configuration.

Public Members

bool locked#

Specify if zoom reference will be used or discarded.

bool filtered#

Filter zoom to have a smoother zoom in, zoom out movement.

bool lossy#

Allow lossy zoom.

float max_vel#

Maximum zoom velocity.

Fov fov#

FOV configuration.

struct Fov#

Field-Of-View configuration.

Public Members

float bound_min#

Minimal FOV in degrees.

float bound_max_lossless#

Maximal FOV in degrees for lossless domain.

float bound_max_lossy#

Maximal FOV in degrees for lossy domain.

float ratio#

Image ratio

struct Reset#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

struct Zoom#

Public Members

Guidance::Camera::Messages::Enum cam#

Selected camera.

::ZoomCamController::Messages::Zoom zoom#

Camera zoom level.

struct Zoom#

Zoom reference.

Public Members

CamController::Messages::ControlMode::Enum ctrl_mode#

Control mode type.

float position#

Zoom level [/].

float velocity#

Zoom velocity [s^-1].

Enumerations#

namespace ControlMode#

Enums

enum Enum#

Values:

enumerator POSITION#

Axis position [rad] or zoom level [/].

enumerator VELOCITY#

Axis velocity [rad/s] or zoom velocity [s^-1].

enumerator POSITION_VELOCITY#

Position velocity.

enumerator NONE#

Target has no frame (target will not be taken into account).

namespace FrameOfReference#

Enums

enum Enum#

Values:

enumerator RELATIVE#

Target is expressed in the frame defined by the latest reference.

enumerator NED#

Target is expressed in NED (North East Down).

enumerator NED_START#

Target is expressed in NED start (North East Down).

enumerator BASE#

Target is expressed in the frame defined by the base.

enumerator NONE#

Target has no frame (target will not be taken into account).

namespace Messages#

Enums

enum Enum#

Values:

enumerator FRONT#

Front camera

enumerator STEREO#

Stereo camera

namespace ReferenceStatus#

Enums

enum Enum#

Values:

enumerator NONE#

No reference set.

enumerator IN_PROGRESS#

Reference is being reached.

enumerator REACHED#

Reference reached.

Modes#

Ascent#

There are no commands for this mode.

Events#
struct Event#

Public Members

google::protobuf::Empty done#

Ascent is completed.

google::protobuf::Empty done_with_immobility#

Ascent is completed and drone is immobile

google::protobuf::Empty done_without_immobility#

Ascent is completed and drone is not immobile

Structure#
struct Config#

Ascent mode configuration

Public Members

Type type#

Ascent type.

float altitude#

Target altitude [m].

Enumeration#
enum Guidance::Ascent::Messages::Type#

Ascent type options

Values:

enumerator TYPE_DEFAULT#

Do not take horizontal piloting commands into account.

enumerator TYPE_MANUAL#

Accept horizontal piloting commands.

Descent#

There are no commands for this mode.

Events#
struct Event#

Union of all possible events of this package.

Public Members

google::protobuf::Empty done#

Descent has been completed successfully

google::protobuf::Empty aborted#

Descent has been aborted

Structure#
struct Config#

Descent mode configuration

Public Members

Type type#

Set up descent type.

TargetType target_type#

Target altitude type.

float altitude#

AGL altitude of descent [m]

float threshold#

Threshold for target reached [m]

float max_speed#

Max custom descent speed [m/s]

Enumeration#
enum Guidance::Descent::Messages::TargetType#

Values:

enumerator TARGET_TYPE_GROUND#

No target type

enumerator TARGET_TYPE_ALTITUDE_AGL#

Special behavior while performing a descent to ground distance

enumerator TARGET_TYPE_ALTITUDE_ATO#

Special behavior while performing a descent to global altitude (above take off)

enum Guidance::Descent::Messages::Type#

Descent Type

Values:

enumerator TYPE_DEFAULT#

Descent type does not take horizontal piloting commands into account.

enumerator TYPE_DEFAULT_PRECISE#

Descent type go on the precise home landing

enumerator TYPE_MANUAL#

Descent type accepts horizontal piloting commands.

enumerator TYPE_GOTOFIX#

Descent type performs a “Go to fix” while descending.

enumerator TYPE_AUTO_LANDING#

Descent type in case of autolanding, accepts horizontal piloting commands.

Emergency Descent#

There are no commands or events for this mode.

Structure#
struct Config#

Emergency descent mode configuration

Public Members

Type type#

Emergency descent type.

bool use_gps#

Whether to use the GPS.

Enumeration#
enum Guidance::EmergencyDescent::Messages::Type#

Emergency descent type

Values:

enumerator TYPE_DEFAULT#

Do not take horizontal piloting commands into account.

enumerator TYPE_MANUAL#

Accept horizontal piloting commands.

Flightplan#

Commands#
struct Command#

Public Members

google::protobuf::Empty pause#

Pause current flightplan, brake and go to fixed point.

google::protobuf::Empty resume#

Resume flightplan

InsertWaypoint insert_waypoint#

Insert waypoint at given index The waypoint that formerly had index i will be shifted to i+1. All subsequent waypoints will be shifted in the same way.

int32 remove_waypoint#

Remove waypoint at given index.

ReplaceWaypoint replace_waypoint#

Replace waypoint at given index with another waypoint.

uint32 set_current_index#

Change current waypoint index.

Events#
struct Event#

Public Members

google::protobuf::Empty done#

The waypoint list has been completed.

WaypointValidated waypoint_validated#

A waypoint has been validated.

WaypointSkipped waypoint_skipped#

A waypoint has been skipped

::Flightplan::Messages::WaypointPath changed#

Flightplan modifications have been accepted return new flightplan

google::protobuf::Empty rejected#

Flightplan modifications have been rejected

Structures#
struct InsertWaypoint#

Public Members

::Flightplan::Messages::Waypoint waypoint#
int32 index#
struct ReplaceWaypoint#

Public Members

::Flightplan::Messages::Waypoint waypoint#
int32 index#
bool keep_original_id#
struct WaypointValidated#

Public Members

int32 current_waypoint_id#

Id of the waypoint being joined after validation

int32 waypoint_id#

Id of the waypoint that was validated

int32 original_id#

Original Id of the waypoint that was validated

struct WaypointSkipped#

Public Members

int32 current_waypoint_id#

Id of the waypoint being joined after skipping waypoint

int32 skipped_waypoint_id#

Id of the waypoint that was skipped

int32 original_id#

Original Id of the waypoint that was skipped

struct Waypoint#

Waypoint containing

  • A View to join (camera position, attitude and zoom factor)

  • A camera behavior (ViewMode) to adopt while joining the waypoint

  • A speed reference to respect while joining the waypoint

  • A type of validation (specifying the criterion to validate the waypoint)

  • A validation radius used for trajectory generation

Public Members

View view#

Camera view on the waypoint.

ViewMode view_mode#

Camera view mode while joining the waypoint - “FREE” if not provided.

Flightplan::Enums::ValidationType::Enum validation_type#

Type of waypoint validation.

float validation_radius#

Waypoint validation radius for sphere waypoints [m].

float speed#

Speed reference for joining the waypoint [m/s].

int32 original_id#

ID of waypoint, >=0 if waypoint is original, <0 if it was added dynamically.

struct WaypointPath#

Series of waypoint

Public Members

Waypoint waypoints[]#

List of waypoints to follow.

uint32 start_at_index#

Starting index, 0 by default.

struct GeoCoordinates#

Public Members

double latitude#

[degree] north

double longitude#

[degree] east

double altitude#

[m] Altitude above takeoff (ATO)

struct NedCoordinates#

Public Members

float north#

[m]

float east#

[m]

float down#

[m]

struct View#

7D viewpoint: 3D position, 3D orientation, 1D zoom factor

Public Members

Position position#

Position of the viewpoint

Orientation orientation#

Orientation of the viewpoint

float zoom_factor#

Zoom factor

struct ViewMode#

Public Members

Flightplan::Enums::ViewMode::Yaw::Enum yaw#

Yaw view mode

Flightplan::Enums::ViewMode::Pitch::Enum pitch#

Pitch view mode

Flightplan::Enums::ViewMode::Roll::Enum roll#

Roll view mode

Flightplan::Enums::ViewMode::Zoom::Enum zoom#

Zoom view mode

Position poi_position#

Position of the point of interest (POI) Taken into account if one of the view modes is ‘poi’

struct Orientation#

Public Members

float roll#

[rad]

float pitch#

[rad]

float yaw#

[rad]

struct Position#

Public Members

GeoCoordinates geo#

Geographic coordinates

NedCoordinates ned#

North-East-Down coordinates

Enumerations#
namespace ValidationType#

Enums

enum Enum#

Validation type

Values:

enumerator STOP#

Stop and wait on the waypoint until it receives an ok to continue.

enumerator SPHERE#

Fly through in a neighborhood of specified radius around the waypoint.

enumerator ARC#

Similar to SPHERE but the turns are circular arcs with a limited turning rate.

namespace Yaw#

Enums

enum Enum#

Yaw view mode

Values:

enumerator FREE#

Unconstrained: No camera reference (reference not updated).

enumerator CONSTANT#

Travelling: Constant camera angle.

enumerator RAMP#

Transition: Reference varies linearly to join the reference on the waypoint.

enumerator POI#

Point Of Interest: Camera tracks a fixed target.

enumerator TANGENT#

Subjective: Camera aligned with its velocity vector.

enumerator SET_ON_WAYPOINT#

FREE mode outside of waypoint validation radius, CONSTANT mode inside.

namespace Pitch#

Enums

enum Enum#

Pitch view mode

Values:

enumerator FREE#

Unconstrained: No camera reference (reference not updated).

enumerator CONSTANT#

Travelling: Constant camera angle.

enumerator RAMP#

Transition: Reference varies linearly to join the reference on the waypoint.

enumerator POI#

Point Of Interest: Camera tracks a fixed target.

enumerator TANGENT#

Subjective: Camera aligned with its velocity vector.

enumerator SET_ON_WAYPOINT#

FREE mode outside of waypoint validation radius, CONSTANT mode inside.

namespace Roll#

Enums

enum Enum#

Roll view mode

Values:

enumerator FREE#

Unconstrained: No camera reference (reference not updated).

enumerator CONSTANT#

Travelling: Constant camera angle.

enumerator RAMP#

Transition: Reference varies linearly to join the reference on the waypoint.

enumerator SET_ON_WAYPOINT#

FREE mode outside of waypoint validation radius, CONSTANT mode inside.

namespace Zoom#

Enums

enum Enum#

Zoom view mode

Values:

enumerator FREE#

No camera reference (reference not updated).

enumerator CONSTANT#

Constant camera zoom.

enumerator RAMP#

Camera zoom varies linearly to join the reference on the waypoint.

enumerator SET_ON_WAYPOINT#

FREE mode outside of waypoint validation radius, CONSTANT mode inside.

Hand Grab#

Structure#
struct Config#

Hand grab modes (Descent/Goto) configuration

Public Members

Type type#

Hand grab type.

Enumeration#
enum Guidance::HandGrab::Messages::Type#

Hand grab type

Values:

enumerator TYPE_POSITION#

Only position will be followed.

enumerator TYPE_POSITION_ORIENTATION#

Position and orientation will be followed.

Hand Launch#

Structure#
struct Config#

Hand launch mode configuration

Public Members

State state#

Hand launch mode state.

FCamBehavior fcam#

Front camera configuration.

Enumeration#
enum Guidance::HandLaunch::Messages::State#

Hand launch mode state

Values:

enumerator STATE_CONSTANT_MIN_THRUST#

Set vertical reference as constant thrust to minimum reachable value, to enable closed loop control.

enumerator STATE_THRUST_RAMP_ZERO_ANGLE#

Set vertical reference as thrust ramp with null horizontal angles reference.

enumerator STATE_CONSTANT_THRUST_ZERO_ANGLE#

Set vertical reference as constant thrust value with null horizontal angles reference.

enumerator STATE_VERTICAL_SPEED_ZERO_ANGLE#

Set vertical reference according to piloting commands with null horizontal angles reference.

enumerator STATE_VERTICAL_SPEED_GO_TO_FIX#

Set vertical reference according to piloting commands and go to fixed point.

Poi#

There are no commands or events for this mode.

Structure#
struct Config#

Point of interest modes configuration

Public Members

Type type#

Point of interest types

float latitude#

Latitude of the point of interest [°].

float longitude#

Longitude of the point of interest [°].

float altitude#

Altitude of the point of interest above takeoff [m].

Enumeration#
enum Guidance::Poi::Messages::Type#

Point of interest type

Values:

enumerator TYPE_FREE#

The pilot has control of the front camera pitch angle.

enumerator TYPE_LOCKED#

The front camera pitch will track the POI altitude.

enumerator TYPE_LOCK_ONCE#

The front camera pitch is locked while reaching requested position and free after then.

Relative Move#

There are no commands for this mode.

Events#
struct Event#

Public Members

Displacement done#

Send effective displacement when done and is last_move

Displacement move_validated#

Send effective displacement when done and is not last_move

Displacement aborted#

Send effective displacement when aborted

Structures#
struct Config#

Relative move mode configuration

Public Members

Displacement displacement#

Requested displacement

bool last_move#

Set to true if this relative move is the last one

struct Displacement#

Relative move displacement The frame of reference is horizontal and relative to the current drone orientation

Public Members

float dx#

Wanted displacement along the front axis [m]

float dy#

Displacement along the right axis [m]

float dz#

Displacement along the down axis [m]

float dyaw#

Change of yaw in the NED frame [rad] clockwise

Drone controller#

address: unix:/tmp/drone-controller

Core#

Commands#

struct Command#

Public Members

ColibryLite::Messages::EstimationMode::Enum set_estimation_mode#

Select drone estimation mode according to the drone state.

google::protobuf::Empty disable_horizontal_control#

Disable horizontal closed loop control.

HorizontalReference set_horizontal_reference#

Modify horizontal reference.

google::protobuf::Empty disable_vertical_control#

Disable vertical closed loop control.

VerticalReference set_vertical_reference#

Modify vertical reference.

google::protobuf::Empty disable_yaw_control#

Disable yaw closed loop control.

YawReference set_yaw_reference#

Modify yaw reference.

google::protobuf::Empty start_motors#

Start all motors. The service will reply with either {motors_started} or {motors_start_failure}.

google::protobuf::Empty stop_all_motors#

Stop all motors. The service will reply with {motors_stopped}.

Events#

struct Event#

Public Members

ColibryLite::Messages::MotionState::Enum motion_state_changed#

Sent when motion state changed (steady, moving).

ColibryLite::Messages::EventDetectionState::Enum moving_ground_state_changed#

Sent when a moving ground has been detected.

google::protobuf::Empty freefall_detected#

Sent when the drone has entered into a freefall phase.

google::protobuf::Empty landed_detected#

Sent when the drone has landed.

google::protobuf::Empty thrust_ramp_done#

Sent when the given thrust target has been reached.

ColibryLite::Messages::EventDetectionState::Enum horizontal_steady#

Sent when the drone is steady in the horizontal plan.

ColibryLite::Messages::EventDetectionState::Enum vertical_steady#

Sent when the drone is steady on the vertical axis.

ColibryLite::Messages::EventDetectionState::Enum yaw_steady#

Sent when the drone is steady on the yaw axis.

google::protobuf::Empty full_steady_ok#

Sent when the drone is steady on all axes (horizontal/vertical/yaw).

google::protobuf::Empty full_steady_ko#

Sent when the drone is not steady on all axes (horizontal/vertical/yaw).

google::protobuf::Empty too_much_angle_detected#

Sent when sensors detected too much pitch/roll angle.

google::protobuf::Empty too_much_angle_detected_at_low_altitude#

Sent when sensors detected too much pitch/roll angle, near ground.

google::protobuf::Empty nominal_angle_detected#

Sent when the pitch/roll angle is nominal.

google::protobuf::Empty nominal_angle_detected_at_low_altitude#

Sent when the pitch/roll angle is nominal, near ground.

google::protobuf::Empty flyaway_detected#

Sent when a vertical flyaway is detected.

TODO: find a better name

google::protobuf::Empty magneto_far_enough_from_earth_poles#

Sent when flying far from earth poles, where horizontal magnetic field is high enough.

google::protobuf::Empty magneto_too_close_to_earth_poles#

Sent when flying near the earth poles, where horizontal magnetic field is too small.

google::protobuf::Empty magnetic_interference_detected#

Sent when sensor magnetic norm is not coherent with earth magnetic norm.

google::protobuf::Empty no_magnetic_interference#

Sent when sensor magnetic norm is coherent with earth magnetic norm.

google::protobuf::Empty freefall_not_detected#

Sent when the drone is not in a freefall phase.

google::protobuf::Empty motors_started#

Sent when motors are started (requested start_motors ok).

google::protobuf::Empty motors_start_failure#

Sent when motors failed to start (requested start_motors ko).

google::protobuf::Empty motors_stopped#

Sent when at least one motor stopped spinning after stop_motors was requested.

google::protobuf::Empty motors_cutout#

Sent when at least one motor stopped spinning, but no request was made to stop motors.

google::protobuf::Empty motors_ramping_done#

Sent when motors reached their target speed before taking off.

MotorsErrorsChanged motors_errors#

Sent when motor errors changed.

MotorsVersion motors_version#

Sent at init with motors version.

MotorsFlightInfo motors_flight_info#

Sent when motors flight info changed.

ColibryLite::Messages::EventDetectionState::Enum hand_takeoff_low_angle#

Sent when pitch/roll angle is low enough after hand takeoff.

ColibryLite::Messages::EventDetectionState::Enum hand_takeoff_low_vertical_speed_error#

Sent when the vertical speed error is low enough after hand takeoff.

ColibryLite::Messages::EventDetectionState::Enum hand_takeoff_low_angular_velocity#

Sent when the angular velocity on both horizontal plane and yaw axis are low enough after hand takeoff.

google::protobuf::Empty linear_velocity_reliable#

Sent when velocity estimation is reliable enough.

google::protobuf::Empty linear_velocity_unreliable#

Sent when velocity estimation is not reliable.

google::protobuf::Empty ground_distance_defective#

Sent when ground distance sensors are defective.

google::protobuf::Empty ground_distance_functional#

Sent when at least one ground distance sensor is not defective.

google::protobuf::Empty thrust_for_angle_reached#

Sent when motors provide the thrust required to enable angle control.

google::protobuf::Empty gps_navigation_ready#

Sent when everything is ready for GPS navigation. The GPS has fixed a location and the geographic north is known.

google::protobuf::Empty gps_navigation_unavailable#

Sent when GPS navigation is unavailable. Either the GPS has not fixed a location or the geographic north is unknown.

google::protobuf::Empty gps_sensor_ok#

Sent when GPS sensor has fixed a location.

google::protobuf::Empty gps_sensor_ko#

Sent when GPS sensor has not fixed a location.

google::protobuf::Empty heading_locked_ok#

Sent when geographic north is known.

google::protobuf::Empty heading_locked_ko#

Sent when geographic north is unknown.

uint32 gps_satellites#

Sent when the number of detected satellites changed.

google::protobuf::Empty vision_navigation_ready#

Sent when everything is ready for vision navigation.

google::protobuf::Empty vision_navigation_unavailable#

Sent when vision navigation is unavailable.

ColibryLite::Messages::WindStatus::Enum wind_status_changed#

Sent when the wind status changed.

ColibryLite::Messages::DefectiveMotorId::Enum defective_motor_id_changed#

Sent when the defective motor status changed.

ColibryLite::Messages::DefectiveMotorFailureType::Enum defective_motor_failure_type_changed#

Sent when the defective motor failure changed.

ColibryLite::Messages::ThreeLevelStatus::Enum vibration_level_changed#

Sent on IMU vibration level changed.

ColibryLite::Messages::ThreeLevelStatus::Enum propeller_icing_level_changed#

Sent on propeller icing level changed.

ColibryLite::Messages::EventDetectionState::Enum battery_shutdown_voltage_reached#

Sent on battery shutdown voltage reached changed.

google::protobuf::Empty magneto_not_calibrated#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_x_done#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_y_done#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_z_done#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_aborted#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_failed#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_done#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_required#

Sent on specific magneto calibration state.

google::protobuf::Empty magneto_calibration_advised#

Sent on specific magneto calibration state.

google::protobuf::Empty min_altitude_constrained#

Sent when requested to go below minimum altitude.

google::protobuf::Empty min_altitude_not_constrained#

Sent when exiting min_altitude_constrained condition.

uint32 defective_sensors_state_changed#

Sent when the state of defective sensors changed.

BatteryState battery_state_changed#

Sent when the battery state changed.

BatteryRole battery_role_changed#

Sent when the battery role changed.

BatteryAlert::Enum battery_alert_too_hot#

Sent when the battery is too hot.

BatteryAlert::Enum battery_alert_too_cold#

Sent when the battery is too cold.

BatteryHealth battery_health#

Sent when the battery health changed.

BatteryAlert::Enum battery_alert_lost_comm#

Sent when a battery defect is detected.

Tick tick#

Notify ticks of the processing loop. It is only sent if a client configured it with {set_tick_notification_config}.

InitStatus init_ok#

Sent at startup when all estimators (etc.) are initialized.

Structures#

struct HorizontalReference#

Public Members

HorizontalAngles angles#

Set horizontal angle references Roll and pitch are defined respectively as the third and second Euler angle of the drone attitude in NED Euler angles mean here the ZYX angle decomposition of a given attitude (yaw, pitch, roll)

HorizontalTrajectoryLocal trajectory_local#

Set linear horizontal trajectory reference The trajectory is given in local frame.

HorizontalTrajectoryGlobal trajectory_global#

Set linear horizontal trajectory reference The trajectory is given in global frame.

HorizontalGoToFix go_to_fix#

Set a null horizontal velocity control (useful for braking)

HorizontalVelocityTrajectory velocity_trajectory#

Set linear horizontal velocity and acceleration references Position, velocity and acceleration are controlled Both velocity and acceleration references are given in north and east axis.

HorizontalVelocity velocity#

Set linear horizontal velocity and acceleration references Only velocity and acceleration are controlled, position control is bypassed. Both velocity and acceleration references are given in north and east axis.

struct VerticalReference#

Union of all kind of vertical reference messages.

Public Members

VerticalVelocity velocity#

Set vertical velocity reference.

This reference is positive downwards.

VerticalVelocityTrajectory velocity_trajectory#

Set vertical velocity trajectory reference.

This reference components (velocity and acceleration) are positive downwards.

VerticalTrajectory trajectory#

Set vertical trajectory reference.

This reference components (position, velocity and acceleration) are positive downwards.

VerticalThrust thrust#

Set vertical normalized thrust.

This reference is positive downwards.

VerticalThrustRamp thrust_ramp#

Set vertical thrust ramp.

This reference is positive downwards.

Thrust will ramp from the current thrust to the target thrust at a given rate.

struct YawReference#

Public Members

YawRate rate#

Set yaw rate reference Euler angles mean here the ZYX angle decomposition of a given attitude (yaw, pitch, roll) Yaw is defined as the first Euler angle which describes the drone attitude in NED start or NED frame (yaw rate is equal in both vector basis).

YawTrajectoryNedStart trajectory_ned_start#

Set yaw trajectory reference Euler angles mean here the ZYX angle decomposition of a given attitude (yaw, pitch, roll) Yaw is defined as the first Euler angle which describes the drone attitude in NED start frame. North reference for NED start frame is defined at power-on (before GPS and magnetometer fix)

YawTrajectoryNed trajectory_ned#

Set yaw angular trajectory reference Euler angles mean here the ZYX angle decomposition of a given attitude (yaw, pitch, roll) Yaw is defined as the first Euler angle which describes the drone attitude in NED frame. North reference for NED frame is true north, defined when yaw alignment is completed (GPS and magnetometer fix available). Before yaw alignment is completed, NED frame will use NED start reference frame

struct TickNotificationConfig#

Public Members

uint32 period#

Number of processing cycles between each tick. A period of zero will stop the notifications. One tick is 5ms (processing loop @200Hz)

struct HorizontalAngles#

Public Members

ColibryLite::Messages::TiltTrajectoryPoint ref#

Tilt trajectory (roll, pitch) in [rad].

ColibryLite::Messages::HorizontalControlConfig::Enum config#

Control mode for horizontal angles.

bool enable_wind_compensation#

True if estimated wind should be compensated by making the drone increase its tilt angle reference.

bool enable_auto_banked_turn#

True if the drone should automatically perform a banked turn.

struct HorizontalTrajectoryLocal#

Public Members

ColibryLite::Messages::HorizontalTrajectoryPoint ref#

Horizontal linear trajectory (X, Y) in local frame.

ColibryLite::Messages::HorizontalControlConfig::Enum config#

Control mode for horizontal trajectory in local frame.

ColibryLite::Messages::HorizontalControllerReactivity::Enum controller_reactivity#

Reactivity of the disturbance rejection controller.

ColibryLite::Messages::ReferencePropagationModel::Enum reference_propagation_model#

Propagation model used for reference trajectory computation

float maximum_horizontal_speed#

Maximum horizontal speed [m/s]. Only taken into account when config == DYNAMIC

struct HorizontalTrajectoryGlobal#

Public Members

ColibryLite::Messages::HorizontalTrajectoryPoint ref#

Horizontal linear trajectory (X, Y) in global frame.

ColibryLite::Messages::HorizontalControlConfig::Enum config#

Control mode for horizontal trajectory in global frame.

ColibryLite::Messages::HorizontalControllerReactivity::Enum controller_reactivity#

Reactivity of the disturbance rejection controller.

ColibryLite::Messages::ReferencePropagationModel::Enum reference_propagation_model#

Propagation model used for reference trajectory computation

float maximum_horizontal_speed#

Maximum horizontal speed [m/s]. Only taken into account when config == DYNAMIC

struct HorizontalGoToFix#

Public Members

ColibryLite::Messages::HorizontalControlConfig::Enum config#

Control mode for horizontal gotofix.

struct HorizontalVelocityTrajectory#

Public Members

ColibryLite::Messages::HorizontalVelocityTrajectory ref#

Horizontal velocity trajectory (X, Y) in north and east axis.

ColibryLite::Messages::HorizontalControlConfig::Enum config#

Control mode for horizontal velocity trajectory.

ColibryLite::Messages::HorizontalControllerReactivity::Enum controller_reactivity#

Reactivity of the disturbance rejection controller.

struct VerticalVelocity#

Public Members

float ref#

Vertical velocity reference [m/s].

ColibryLite::Messages::VerticalControlConfig::Enum config#

Control mode for vertical velocity.

ColibryLite::Messages::VerticalControllerSetting::Enum controller_setting#

Vertical controller setting.

bool ground_constrained#

True if descent is limited to a minimum altitude above ground.

struct VerticalTrajectory#

Public Members

ColibryLite::Messages::TrajectoryPoint ref#

Vertical trajectory reference.

ColibryLite::Messages::VerticalControlConfig::Enum config#

Control mode for vertical trajectory.

ColibryLite::Messages::VerticalControllerSetting::Enum controller_setting#

Vertical controller setting.

ColibryLite::Messages::ReferencePropagationModel::Enum reference_propagation_model#

Propagation model used for reference trajectory computation

bool ground_constrained#

True if descent is limited to a minimum altitude above ground.

float maximum_vertical_speed#

Maximum vertical speed [m/s]. Only taken into account when config == DYNAMIC

struct VerticalThrust#

Public Members

float ref#

Vertical thrust, normalized by the drone mass [m.s^-2]

ColibryLite::Messages::VerticalControlConfig::Enum config#

Control mode for vertical thrust.

struct VerticalThrustRamp#

Public Members

float ref#

Vertical thrust target, normalized by drone mass [m.s^-2].

float rate#

Vertical thrust change rate, normalized by drone mass [m.s^-3].

ColibryLite::Messages::VerticalControlConfig::Enum config#

Control mode for vertical thrust ramp.

struct YawRate#

Public Members

float ref#

Yaw rate reference [rad/s].

ColibryLite::Messages::YawControlConfig::Enum config#

Yaw control mode.

struct YawTrajectoryNed#

Public Members

ColibryLite::Messages::TrajectoryPoint ref#

Yaw trajectory reference in NED vector basis.

ColibryLite::Messages::YawControlConfig::Enum config#

Yaw control mode.

ColibryLite::Messages::ReferencePropagationModel::Enum reference_propagation_model#

Propagation model used for reference trajectory computation

bool use_shortest_path#

Use the shortest path from current yaw reference.

float maximum_yaw_angular_rate#

Maximum angular rate [rad/s]. Only taken into account when config == DYNAMIC

struct YawTrajectoryNedStart#

Public Members

ColibryLite::Messages::TrajectoryPoint ref#

Yaw trajectory reference in NED start vector basis.

ColibryLite::Messages::YawControlConfig::Enum config#

Yaw control mode.

ColibryLite::Messages::ReferencePropagationModel::Enum reference_propagation_model#

Propagation model used for reference trajectory computation

bool use_shortest_path#

Use the shortest path from current yaw reference.

float maximum_yaw_angular_rate#

Maximum angular rate [rad/s]. Only taken into account when config == DYNAMIC

struct BatteryHealth#

Public Members

uint32 state_of_health#

Battery state of health [%].

uint32 cycle_count#

Battery cycle count.

struct BatteryRole#

Public Members

BatteryDataRole::Enum data_role#
BatteryPowerRole::Enum power_role#
struct BatteryState#

Battery alert events

Public Members

float voltage#

Current battery voltage [V].

int32 level#

Current charge level, aka. state of charge [%].

uint32 remaining_cap#

Remaining battery capacity [Ah].

uint32 full_charge_cap#

Full charge battery capacity [Ah].

bool is_smartbattery#

Indicate if battery is a SmartBattery.

struct InitStatus#

Public Members

bool flying#

True when motors are in motion

struct MotorErrorChange#

Public Members

uint32 index#
MotorError::Enum value#
struct MotorsErrorsChanged#

Public Members

MotorErrorChange errors[]#

one entry for each motor error change.

struct MotorsFlightInfo#

Public Members

uint32 nb_flights#

Current flight number

uint32 previous_time#

Previous flight time [s]

uint32 total_time#

Total flight time [s]

MotorError::Enum last_error#

Last error seen on motors

struct MotorsVersion#

Public Members

uint32 hard_version#
uint32 major_version#
uint32 minor_version#
uint32 type_version#

char

uint32 motors_count#
struct Tick#

Public Members

uint32 num#

Tick sequence number.

uint64 timestamp_us#

Tick timestamp [us].

Enumerations#

namespace BatteryAlert#

Enums

enum Enum#

Alert level for a battery alert

Values:

enumerator NONE#

No alert.

enumerator WARNING#

Warning alert level.

enumerator CRITICAL#

Critical alert level.

namespace BatteryDataRole#

Enums

enum Enum#

Values:

enumerator NONE#

Unknown data role.

enumerator HOST#

Usb on battery is Host.

enumerator DEVICE#

Usb on battery is device.

namespace BatteryPowerRole#

Enums

enum Enum#

Values:

enumerator NONE#

Unknown power role.

enumerator SOURCE#

Battery is powering the drone.

enumerator SINK#

Battery is being powered externally.

namespace MotorError#

Enums

enum Enum#

Values:

enumerator NONE#

No error detected.

enumerator EEPROM#

EEPROM access failure.

enumerator MOTOR_STALLED#

Motor stalled.

enumerator PROPELLER_SECURITY#

Propeller cutout security triggered.

enumerator COMM_LOST#

Communication with motor failed by timeout.

enumerator RC_EMERGENCY_STOP#

RC emergency stop.

enumerator REAL_TIME#

Motor controller scheduler real-time out of bounds.

enumerator MOTOR_SETTING#

One or several incorrect values in motor settings.

enumerator TEMPERATURE#

Too hot or too cold Cypress temperature.

enumerator BATTERY_VOLTAGE#

Battery voltage out of bounds

enumerator LIPO_CELLS#

Incorrect number of LIPO cells.

enumerator MOSFETS#

Defective MOSFET or broken motor phases.

enumerator BOOTLOADER#

Not use for BLDC but useful for HAL.

enumerator ASSERT#

Error Made by BLDC_ASSERT().

ColibryLite#

Structures#

struct HorizontalTrajectoryPoint#

Horizontal (x, y) trajectory

Public Members

TrajectoryPoint x#
TrajectoryPoint y#
struct HorizontalVelocityTrajectory#

Horizontal (x, y) velocity trajectory

struct TiltTrajectoryPoint#

Tilt (phi, theta) trajectory

Public Members

TrajectoryPoint phi#
TrajectoryPoint theta#
struct TrajectoryPoint#

Generic trajectory

Public Members

float x#

Position

float dx#

Velocity

float ddx#

Acceleration

struct VelocityTrajectory#

Generic velocity trajectory

Public Members

float x#

Velocity

float dx#

Acceleration

Enumerations#

namespace DefectiveMotorId#

Enums

enum Enum#

Values:

enumerator FRONT_LEFT#

Front left motor down.

enumerator FRONT_RIGHT#

Front right motor down.

enumerator REAR_RIGHT#

Rear right motor down.

enumerator REAR_LEFT#

Rear left motor down.

enumerator NONE#

Default: all motors running.

namespace EstimationMode#

Enums

enum Enum#

Values:

enumerator INIT#

Estimators initialization at autopilot start.

enumerator MOTORS_STOPPED#

Motors stopped.

enumerator USER_MAGNETO_CALIBRATION#

User magnetometer calibration performed on the ground.

enumerator MOTORS_STARTING_STOPPING#

Starting motors before takeoff or stopping motors after landing (ESC in open-loop).

enumerator MOTORS_RAMPING#

Motors ramping until reaching the speed to leave the ground.

enumerator TAKEOFF#

Takeoff ascent phase.

enumerator WAIT_FREEFALL#

Wait for free fall.

enumerator RESCUE#

Angular and linear stabilization phase after free fall.

enumerator FLYING#

Hovering and flying states.

enumerator LANDING#

Landing descent phase.

enumerator EMERGENCY_LANDING#

Emergency descent phase.

enumerator LANDING_UNSTEADY_SURFACE#

Landing descent phase on unsteady surface (hand, vehicle…).

enumerator TAKEOFF_UNSTEADY_SURFACE#

Takeoff ascent phase on unsteady surface (vehicle…)

namespace EventDetectionState#

Enums

enum Enum#

Values:

enumerator S_FALSE#
enumerator S_TRUE#
enumerator S_UNKNOWN#
namespace HorizontalControlConfig#

Enums

enum Enum#

Values:

enumerator DEFAULT#

Default configuration.

Maximum horizontal speed: 12 m/s

Maximum horizontal acceleration: 4 m/s²

Maximum pitch/roll angles: 30° (but can be changed according to altitude)

Maximum pitch/roll angular rates: 200°/s

enumerator AGGRESSIVE#

Fast and aggressive config.

Maximum horizontal speed: 15 m/s

Maximum horizontal acceleration: 5 m/s²

Maximum pitch/roll angles: 30° (but can be changed according to altitude)

Maximum pitch/roll angular rates: 300°/s

enumerator SOFT#

Slow and smooth config.

Maximum horizontal speed: 7 m/s

Maximum horizontal acceleration: 1.5 m/s²

Maximum pitch/roll angles: 30° (but can be changed according to altitude)

Maximum pitch/roll angular rates: 80°/s

enumerator DYNAMIC#

Customizable speed config.

Maximum horizontal speed: from reference message (but never higher than 12 ms/s)

Maximum horizontal acceleration: 4 m/s²

Maximum pitch/roll angles: 30° (but can be changed according to altitude)

Maximum pitch/roll angular rates: 300°/s

namespace MotionState#

Enums

enum Enum#

Values:

enumerator STEADY#

No motion detected and the motors are off.

enumerator MOVING#

Drone is moving.

namespace ReferencePropagationModel#

Enums

enum Enum#

Values:

enumerator IDEAL_MODEL#

Reference trajectory is computed using the ideal model.

enumerator TRIPLE_INTEGRATOR#

Reference trajectory is computed by integrating the input trajectory.

namespace ThreeLevelStatus#

Enums

enum Enum#

Values:

enumerator OK#
enumerator WARNING#
enumerator CRITICAL#
namespace VerticalControlConfig#

Enums

enum Enum#

Values:

enumerator DEFAULT#

Default configuration.

Maximum upward speed: 3 m/s

Maximum downward speed: 3 m/s

Maximum upward acceleration: 3 m/s²

Maximum downward acceleration: 3 m/s²

enumerator SOFT#

Slow and smooth config.

Maximum upward speed: 1 m/s

Maximum downward speed: 1 m/s

Maximum upward acceleration: 2 m/s²

Maximum downward acceleration: 2 m/s²

enumerator AGGRESSIVE#

Fast and aggressive config.

Maximum upward speed: 4 m/s

Maximum downward speed: 3 m/s

Maximum upward acceleration: 6 m/s²

Maximum downward acceleration: 5 m/s²

enumerator DYNAMIC#

Customizable speed config.

Maximum upward speed: from reference message (but never higher than 4 m/s)

Maximum downward speed: from reference message (but never higher than 3 m/s)

Maximum upward acceleration: 6 m/s²

Maximum downward acceleration: 5 m/s²

namespace WindStatus#

Enums

enum Enum#

Values:

enumerator OK#

Mean wind speed is below warning threshold

enumerator WARNING#

Mean wind speed is above warning threshold

enumerator CRITICAL#

Mean wind speed is critical and can limit the whole flight performances.

namespace YawControlConfig#

Enums

enum Enum#

Values:

enumerator DEFAULT#

Default ideal model Maximum command angular rate: 100 °/s Maximum angular rate: 180 °/s

enumerator SOFT#

Slow and smooth ideal model Maximum command angular rate: 60 °/s Maximum angular rate: 45 °/s

enumerator AGGRESSIVE#

Aggressive ideal model Maximum command angular rate: 235 °/s Maximum angular rate: 235 °/s

enumerator DYNAMIC#

Customizable speed config with default ideal model Maximum command angular rate: from reference message (but never higher than 235 °/s) Maximum angular rate: from reference message (but never higher than 235 °/s)

Computer vision#

Computer vision exposes control on different features:

  • visual tracking: this feature will enhance the tracking of a target with image and deep learning processing. Once enable, a mission may select the target with the dedicated commands described hereafter.

  • precise hovering feature: this feature enhances hovering flying state by providing accurate estimations of drone position to the flight controller.

    Two different computer vision algorithms are available (can work simultaneously)

    • hovering 3d: takes video frames from stereo camera (in its current position) and take advantage of the depth to provide position estimations.

    • hovering 2d: takes video frames from the vertical monocular camera to provide drone position estimation. (always available)

  • precise home feature: this feature enhances the ‘Return To Home’ feature by providing during the landing stage an accurate position of the drone relatively to the initial take off frame.

Here are the messages to use them.

Tracking#

address: unix:/tmp/selkie

Commands#

struct Command#

Union of all possible commands of this package.

Public Members

Enable enable#
google::protobuf::Empty disable#
Target target#
SetRect set_rect#
SetId set_id#
RemoveId remove_id#
google::protobuf::Empty stop_all_tracking#

Events#

struct Event#

Union of all possible events of this package.

Public Members

TrackingStates states#
Answer answer#
Availability availability#

Structures#

struct Enable#

Enable tracking with or without box proposal.

Public Members

bool with_boxprop#
struct Rect#

Normalized rectangle inside the streamed image.

Public Members

float left_x#
float top_y#
float width#
float height#
struct RemoveId#

Remove the tracking on a target using its id.

Public Members

uint32 id#

Identification of the box id to stop tracking.

struct SetId#

Set a new target using an id from the proposed targets.

Public Members

uint32 id#

Identification of one of the proposed boxes.

uint32 cookie#

The cookie is chosen by the client to identify the request and will be provided with any result relative to this request.

SetMode mode#
uint64 ts_us#

Timestamp that was associated to the frame on which the box was selected.

struct SetRect#

Set a new target using a rectangle.

Public Members

Rect rect#
uint32 cookie#

The cookie is chosen by the client to identify the request and will be provided with any result relative to this request.

SetMode mode#
uint64 ts_us#

Timestamp that was associated to the frame on which the selection rectangle was drawn.

struct Target#

Target position strategy.

Public Types

enum Position#

Values:

enumerator NONE#

Don’t use a target position.

enumerator PILOT_ESTIMATION#

Use position from pilot estimation.

Public Members

Position position#
struct TrackingStates#

Tracking states for all the targets

Public Members

TrackingState states[]#
struct TrackingState#

Tracking state of a target.

Public Members

uint32 id#

Target box identification.

uint32 cookie#

Client identification chosen at the SetId or SetRect command.

Status status#

Tracking status.

Enumerations#

enum CvTrackingService::Messages::Answer#

Answer to a tracking request.

Values:

enumerator PROCESSED#

The tracking request is being processed.

enumerator TARGET_LIMIT_REACHED#

The request is refused because we are at the limit of the number of targets we can track at the same time.

enumerator NOT_FOUND#

The described target doesn’t exists (wrong id…).

enumerator INVALID#

The tracking request is invalid.

enum CvTrackingService::Messages::Availability#

Availability of the visual tracking feature.

Values:

enumerator AVAILABLE#
enumerator NOT_AVAILABLE#
enum CvTrackingService::Messages::SetMode#

Set target mode while setting a new target.

Values:

enumerator ADD#

Add a new target to the previous ones (if not above the total number of trackable targets).

enumerator REPLACE#

Replace the previous target with the new one.

enum CvTrackingService::Messages::Status#

Tracking status of a target.

Values:

enumerator TRACKING#

The target is tracked.

enumerator SEARCHING#

The target is lost but still searched for.

enumerator ABANDON#

The target is lost and research has been abandoned.

Hovering#

address: unix:@pimp-hovering

Commands#

struct Command#

Public Members

Void start_estimate_3d#
Void stop_3d#
Void start_2d#
Void stop_2d#

Events#

struct Event#

Public Members

Result start_estimate_3d#
Result start_evaluate_3d#
Result stop_3d#
Result start_2d#
Result stop_2d#

Enumerations#

struct Result#

Public Types

enum ResultVal#

Values:

enumerator OK#
enumerator ERROR_GENERIC#
enumerator ERROR_ALREADY_IN_STATE#
enumerator ERROR_IGNORED#

Public Members

ResultVal result#

Precise home#

address: unix:@pimp-hovering

Commands#

struct Command#

Public Members

Void set_ground_pos#

Store drone ground position before takeoff

Void set_heading_is_locked#

Notify precise home that yaw alignment is completed

Void reset_score#

Notify precise home to reset its scoring system but keep reference image

Void set_ref_image#

Store picture from vertical camera at the end of takeoff

Void start_compute#

Start process to estimate motion from current drone position to takeoff area

Void stop_compute#

End process

Events#

struct Event#

Public Members

Result new_result#
struct Result#

data structure for event result

Public Types

enum PreciseHomeStatus#

Values:

enumerator NOT_AVAILABLE#

No reference image, cannot compute

enumerator AVAILABLE#

Ready to compute, reference image available.

enumerator SEARCHING#

Computing, home position not found yet.

enumerator FOUND#

Home position found, computation was made to improve accuracy.

Public Members

PreciseHomeStatus status#

Camera failures#

address: unix:/tmp/heimdall

Commands#

struct Command#

Union of all possible commands of this package.

TODO: add the proper commands when known

Public Members

google::protobuf::Empty decal_detector_start#
google::protobuf::Empty decal_detector_stop#
Camera calibration_start#
CalibrationStop calibration_stop#

Events#

struct Event#

Public Members

Camera nominal#
Camera failure#
Camera decalibration_failure_start#
Camera decalibration_failure_stop#
Camera too_dark_failure_start#
Camera too_dark_failure_stop#
Camera stabilization_failure_start#
Camera stabilization_failure_stop#
Camera sensor_failure_start#
Camera sensor_failure_stop#
Camera led_on#
Camera led_off#
Camera calibration_running_start#
Camera calibration_running_stop#

Structures#

struct Camera#

Public Types

enum CameraId#

Values:

enumerator FSTCAM#

front stereo camera

enumerator VCAM#

vertical camera

enumerator FCAM#

front camera

Public Members

CameraId camera#