MAV'RIC
Classes | Public Member Functions | Static Public Member Functions | Public Attributes | Friends
State Class Reference

The MAV state. More...

#include <state.hpp>

Collaboration diagram for State:
Collaboration graph
[legend]

List of all members.

Classes

struct  conf_t
 Configuration structure. More...

Public Member Functions

 State (Mavlink_stream &mavlink_stream_, Battery &battery, conf_t config=default_config())
 Constructor.
void switch_to_active_mode (mav_state_t *mav_state_)
 Makes the switch to active mode.
void connection_status ()
 Check the connection status with the GND station.
bool set_armed (bool arming)
 tries to arm/disarm; checks performed for arming
bool is_armed () const
 returns whether armed
bool is_manual () const
 returns whether in manual mode
bool is_hil () const
 returns whether in hil mode
bool is_stabilize () const
 returns whether in stabilize mode
bool is_guided () const
 returns whether in guided mode
bool is_auto () const
 returns whether in auto mode
bool is_custom () const
 returns whether in custom mode
bool is_test () const
 returns whether in test mode
Mav_mode mav_mode () const
 returns mav_mode (copy)

Static Public Member Functions

static conf_t default_config ()
 Default configuration for quadrotor.
static conf_t wing_default_config ()
 Default configuration for wing.

Public Attributes

mav_state_t mav_state_
 The value of the MAV state.
Mav_mode mav_mode_
 The value of the MAV mode.
Mav_mode::custom_mode_t mav_mode_custom
 The value of the custom_mode.
uint8_t autopilot_type
 The type of the autopilot (MAV_TYPE enum in common.h)
uint8_t autopilot_name
 The name of the autopilot (MAV_AUTOPILOT enum in common.h)
uint32_t sensor_present
 The type of sensors that are present on the autopilot (Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control)
uint32_t sensor_enabled
 The sensors enabled on the autopilot (Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control)
uint32_t sensor_health
 The health of sensors present on the autopilot (Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control)
bool out_of_safety_geofence
 Flag to tell whether we are out the first fence or not.
bool out_of_emergency_geofence
 Flag to tell whether we are out the second fence or not.
bool reset_position
 Flag to enable the reset of the position estimation.
double last_heartbeat_msg
 Time of reception of the last heartbeat message from the ground station.
double max_lost_connection
 Maximum time without reception of a heartbeat message from the ground station.
uint32_t msg_count
 Number of heartbeat message received from the Ground station.
bool connection_lost
 Flag to tell if we have connection with the GND station or not.
bool first_connection_set
 Flag to tell that we received a first message from the GND station.
Batterybattery_
 Pointer to battery structure.

Friends

class State_machine
bool state_telemetry_set_mode (State *state, Mav_mode mav_mode)
mav_result_t state_telemetry_send_autopilot_capabilities (State *state, const mavlink_command_long_t *packet)
 Callback to the command 520 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.

Detailed Description

The MAV state.


Constructor & Destructor Documentation

State::State ( Mavlink_stream mavlink_stream_,
Battery battery,
State::conf_t  config = default_config() 
)

Constructor.

Parameters:
mavlink_streamMavlink downlink
batteryBattery monitor
state_configState configuration structure

Here is the call graph for this function:


Member Function Documentation

State::conf_t State::default_config ( void  ) [inline, static]

Default configuration for quadrotor.

Returns:
Config structure
bool State::is_armed ( ) const [inline]

returns whether armed

Returns:
armed

Here is the call graph for this function:

Here is the caller graph for this function:

bool State::is_auto ( ) const [inline]

returns whether in auto mode

Returns:
auto

Here is the call graph for this function:

Here is the caller graph for this function:

bool State::is_custom ( ) const [inline]

returns whether in custom mode

Returns:
custom

Here is the call graph for this function:

bool State::is_guided ( ) const [inline]

returns whether in guided mode

Returns:
guided

Here is the call graph for this function:

bool State::is_hil ( ) const [inline]

returns whether in hil mode

Returns:
hil

Here is the call graph for this function:

bool State::is_manual ( ) const [inline]

returns whether in manual mode

Returns:
manual

Here is the call graph for this function:

bool State::is_stabilize ( ) const [inline]

returns whether in stabilize mode

Returns:
stabilize

Here is the call graph for this function:

bool State::is_test ( ) const [inline]

returns whether in test mode

Returns:
test

Here is the call graph for this function:

Mav_mode State::mav_mode ( ) const [inline]

returns mav_mode (copy)

Returns:
mav_mode

Here is the caller graph for this function:

bool State::set_armed ( bool  arming)

tries to arm/disarm; checks performed for arming

arming is prevented if

  • IMU not ready (mav_state_ == MAV_STATE_CALIBRATING)
  • in manual and guided or stabilised mode
  • battery low
Parameters:
armingtrue for arming, false for disarming
Returns:
true if desired arming state was accepted; false if refused

Here is the call graph for this function:

Here is the caller graph for this function:

void State::switch_to_active_mode ( mav_state_t *  mav_state_)

Makes the switch to active mode.

Parameters:
mav_state_MAV state

Here is the caller graph for this function:

Default configuration for wing.

Returns:
Config structure

Friends And Related Function Documentation

mav_result_t state_telemetry_send_autopilot_capabilities ( State state,
const mavlink_command_long_t *  packet 
) [friend]

Callback to the command 520 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.

Parameters:
stateThe pointer to the state structure
packetThe pointer to the decoded MAVLink message long
Returns:
The MAV_RESULT of the command

The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines