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 (
enum.FlightplanWaypointEvt
) - Events associated to a certain waypoint in a FlightPlan.num (uint32) - Waypoint number.
-
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 themove_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.
-
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.
-
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.
-
TimeOut time_out#
Structures#
-
struct PowerAlertBatteryLevel#
Public Members
-
::PowerAlerts::BatteryPowerLevel::Enum level#
Power level.
-
::PowerAlerts::BatteryPowerLevel::Enum level#
-
struct PowerAlertRthCapacity#
Public Members
-
::PowerAlerts::RthBatteryCapacity::Enum capacity#
RTH battery capacity.
-
::PowerAlerts::RthBatteryCapacity::Enum capacity#
-
struct PcmdHoriz#
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
-
enumerator SHUTDOWN#
-
enum Enum#
-
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.
-
enumerator OK#
-
enum Enum#
-
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#
Core#
Guidance#
Commands#
-
struct Command#
Public Members
-
bool set_obstacle_avoidance#
Enable or disable obstacle avoidance.
-
bool set_geofence#
Enable or disable geofence.
-
GeofenceCenter set_geofence_center#
Set geofence center.
-
bool set_obstacle_avoidance#
Events#
-
struct Event#
Public Members
-
ModeChanged mode_changed#
Acknowledgment of
set_mode
command.
-
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.
-
ModeChanged mode_changed#
Structures#
-
struct Error#
-
struct GeofenceCenter#
-
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.
-
bool ok#
-
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).
-
float roll#
-
struct SetMode#
TODO rename into ModeConfig
AxesCamController#
Commands#
-
struct Command#
Events#
-
struct Event#
Public Members
-
ReferenceStatus reference_status#
Camera axes reference status
-
Capabilities capabilities#
Camera axes capabilities advertised when a client connects.
-
ReferenceStatus reference_status#
Structures#
-
struct AxisConfig#
Axis configuration.
-
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].
-
CamController::Messages::ControlMode::Enum ctrl_mode#
-
struct Capabilities#
Public Members
-
bool yaw_drivable#
Yaw axis drivable.
-
bool pitch_drivable#
Pitch axis drivable.
-
bool roll_drivable#
Roll axis drivable.
-
struct Bounds#
-
bool yaw_drivable#
-
struct Config#
-
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.
-
CamController::Messages::AxisConfig yaw#
-
struct Reference#
-
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.
-
CamController::Messages::AxisReference yaw#
-
struct ReferenceStatus#
Public Members
-
::AxesCamController::Messages::ReferenceStatus status#
Camera axes status.
-
::AxesCamController::Messages::ReferenceStatus 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.
-
CamController::Messages::ReferenceStatus::Enum yaw#
-
struct Reset#
ZoomCamController#
Commands#
-
struct Command#
Events#
-
struct Event#
Structures#
-
struct Config#
-
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.
-
struct Fov#
Field-Of-View configuration.
-
bool locked#
-
struct Reset#
-
struct Zoom#
Enumerations#
-
namespace ControlMode#
-
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).
-
enumerator RELATIVE#
-
enum Enum#
-
namespace Messages#
-
namespace ReferenceStatus#
Modes#
Ascent#
There are no commands for this mode.
Events#
-
struct Event#
Structure#
-
struct Config#
Ascent mode configuration
Enumeration#
Descent#
There are no commands for this mode.
Events#
-
struct Event#
Union of all possible events of this package.
Structure#
-
struct Config#
Descent mode configuration
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)
-
enumerator TARGET_TYPE_GROUND#
-
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.
-
enumerator TYPE_DEFAULT#
Emergency Descent#
There are no commands or events for this mode.
Structure#
-
struct Config#
Emergency descent mode configuration
Enumeration#
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.
-
google::protobuf::Empty pause#
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
-
google::protobuf::Empty done#
Structures#
-
struct InsertWaypoint#
-
struct ReplaceWaypoint#
-
struct WaypointValidated#
-
struct WaypointSkipped#
-
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
-
Flightplan::Enums::ValidationType::Enum validation_type#
Type of waypoint validation.
-
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
-
struct GeoCoordinates#
-
struct NedCoordinates#
-
struct View#
7D viewpoint: 3D position, 3D orientation, 1D zoom factor
-
struct ViewMode#
Public Members
-
struct Orientation#
-
struct Position#
Public Members
-
GeoCoordinates geo#
Geographic coordinates
-
NedCoordinates ned#
North-East-Down coordinates
-
GeoCoordinates geo#
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.
-
enumerator STOP#
-
enum Enum#
-
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.
-
enumerator FREE#
-
enum Enum#
-
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.
-
enumerator FREE#
-
enum Enum#
-
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.
-
enumerator FREE#
-
enum Enum#
-
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.
-
enumerator FREE#
-
enum Enum#
Hand Grab#
Structure#
-
struct Config#
Hand grab modes (Descent/Goto) configuration
Enumeration#
Hand Launch#
Structure#
-
struct Config#
Hand launch mode 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.
-
enumerator STATE_CONSTANT_MIN_THRUST#
Poi#
There are no commands or events for this mode.
Structure#
-
struct Config#
Point of interest modes configuration
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.
-
enumerator TYPE_FREE#
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 done#
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
-
Displacement displacement#
-
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
-
float dx#
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}.
-
ColibryLite::Messages::EstimationMode::Enum set_estimation_mode#
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.
Sent when everything is ready for GPS navigation. The GPS has fixed a location and the geographic north is known.
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.
Sent when everything is ready for vision navigation.
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.
-
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.
-
ColibryLite::Messages::MotionState::Enum motion_state_changed#
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.
-
HorizontalAngles angles#
-
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.
-
VerticalVelocity velocity#
-
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
-
YawRate rate#
-
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)
-
uint32 period#
-
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.
-
ColibryLite::Messages::TiltTrajectoryPoint ref#
-
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
-
ColibryLite::Messages::HorizontalTrajectoryPoint ref#
-
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
-
ColibryLite::Messages::HorizontalTrajectoryPoint ref#
-
struct HorizontalGoToFix#
Public Members
-
ColibryLite::Messages::HorizontalControlConfig::Enum config#
Control mode for horizontal gotofix.
-
ColibryLite::Messages::HorizontalControlConfig::Enum config#
-
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.
-
ColibryLite::Messages::HorizontalVelocityTrajectory ref#
-
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.
-
float ref#
-
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
-
ColibryLite::Messages::TrajectoryPoint ref#
-
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.
-
float ref#
-
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.
-
float ref#
-
struct YawRate#
Public Members
-
float ref#
Yaw rate reference [rad/s].
-
ColibryLite::Messages::YawControlConfig::Enum config#
Yaw control mode.
-
float ref#
-
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
-
ColibryLite::Messages::TrajectoryPoint ref#
-
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
-
ColibryLite::Messages::TrajectoryPoint ref#
-
struct BatteryHealth#
-
struct BatteryRole#
-
struct BatteryState#
Battery alert events
-
struct MotorErrorChange#
-
struct MotorsErrorsChanged#
Public Members
-
MotorErrorChange errors[]#
one entry for each motor error change.
-
MotorErrorChange errors[]#
-
struct MotorsFlightInfo#
-
struct MotorsVersion#
-
struct Tick#
Enumerations#
-
namespace BatteryAlert#
-
namespace BatteryDataRole#
-
namespace BatteryPowerRole#
-
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().
-
enumerator NONE#
-
enum Enum#
ColibryLite#
Structures#
-
struct HorizontalTrajectoryPoint#
Horizontal (x, y) trajectory
-
struct HorizontalVelocityTrajectory#
Horizontal (x, y) velocity trajectory
-
struct TiltTrajectoryPoint#
Tilt (phi, theta) trajectory
-
struct TrajectoryPoint#
Generic trajectory
-
struct VelocityTrajectory#
Generic velocity trajectory
Enumerations#
-
namespace DefectiveMotorId#
-
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…)
-
enumerator INIT#
-
enum Enum#
-
namespace EventDetectionState#
-
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°
Maximum pitch/roll angular rates: 300°/s
-
enumerator AGGRESSIVE#
Fast and aggressive config.
Maximum horizontal speed: 15 m/s
Maximum horizontal acceleration: 6 m/s²
Maximum pitch/roll angles: 30°
Maximum pitch/roll angular rates: 600°/s
-
enumerator SOFT#
Slow and smooth config.
Maximum horizontal speed: 8 m/s
Maximum horizontal acceleration: 2 m/s²
Maximum pitch/roll angles: 20°
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°
Maximum pitch/roll angular rates: 300°/s
-
enumerator DEFAULT#
-
enum Enum#
-
namespace MotionState#
-
namespace ReferencePropagationModel#
-
namespace ThreeLevelStatus#
-
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²
-
enumerator DEFAULT#
-
enum Enum#
-
namespace WindStatus#
-
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)
-
enumerator DEFAULT#
-
enum Enum#
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#
Commands#
-
struct Command#
Union of all possible commands of this package.
Events#
-
struct Event#
Union of all possible events of this package.
Structures#
-
struct Rect#
Normalized rectangle inside the streamed image.
-
struct RemoveId#
Remove the tracking on a target using its id.
Public Members
-
uint32 id#
Identification of the box id to stop tracking.
-
uint32 id#
-
struct SetId#
Set a new target using an id from the proposed targets.
-
struct SetRect#
Set a new target using a rectangle.
-
struct TrackingStates#
Tracking states for all the targets
Public Members
-
TrackingState states[]#
-
TrackingState states[]#
-
struct TrackingState#
Tracking state of a target.
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.
-
enumerator PROCESSED#
-
enum CvTrackingService::Messages::Availability#
Availability of the visual tracking feature.
Values:
-
enumerator AVAILABLE#
-
enumerator NOT_AVAILABLE#
-
enumerator AVAILABLE#
Hovering#
Commands#
-
struct Command#
Events#
-
struct Event#
Enumerations#
Precise home#
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
-
Void set_ground_pos#
Events#
Camera failures#
Commands#
-
struct Command#
Union of all possible commands of this package.
TODO: add the proper commands when known
Events#
-
struct Event#
Public Members