Public Member Functions | Private Attributes
fcu::FlightController Class Reference

#include <FlightController.hpp>

List of all members.

Public Member Functions

bool connect (const std::string &device, const size_t baudrate=115200, const double &timeout=0.0, const bool print_info=false)
 Connects to a physical flight controller, which includes connecting the internal Client object and querying the flight controller for information necessary to configure the internal state to match the capabiliites of the flight controller.
bool disconnect ()
 Stops MSP control if active, and disconnects the internal Client object.
 FlightController ()
 FlightController Constructor.
void generateMSP ()
 Method used to generate the Rc message sent to the flight controller.
std::string getBoardName () const
 Queries the currently set board name.
const std::map< std::string,
size_t > & 
getBoxNames () const
 Gets the information collected by the initBoxes() method.
ControlSource getControlSource ()
 Queries the currently active control source.
FlightMode getFlightMode () const
 Queries data structure with all flags governing flight mode.
msp::FirmwareVariant getFwVariant () const
 Queries the currently set firmware variant (Cleanflight, Betaflight, etc.)
int getProtocolVersion () const
 Queries the currently set protocol (MSPv1 or MSPv2)
std::shared_ptr
< msp::client::SubscriptionBase
getSubscription (const msp::ID &id)
 Get pointer to subscription.
bool hasAccelerometer () const
 Queries for the presence of an accelerometer.
bool hasBarometer () const
 Queries for the presence of a barometer.
bool hasBind () const
 Queries for the presence of the BIND capability.
bool hasCapability (const msp::msg::Capability &cap) const
 Queries the cached flight controller information to see if a particular capability is present.
bool hasDynBal () const
 Queries for the presence of the DYNBAL capability.
bool hasFlap () const
 Queries for the presence of the FLAP capability.
bool hasGPS () const
 Queries for the presence of a GPS.
bool hasMagnetometer () const
 Queries for the presence of a magentometer.
bool hasSensor (const msp::msg::Sensor &sensor) const
 Queries the cached flight controller information to see if a particular sensor is present.
bool hasSonar () const
 Queries for the presence of a sonar.
bool hasSubscription (const msp::ID &id) const
 Check if message ID is subscribed.
void initBoxes ()
 Queries the flight controller for Box (flight mode) information.
bool isArmed ()
 Queries the flight controller to see if the ARM status is active. Not to be confused with armSet(), which queries whether the flight controller has been instructued to turn on the ARM status.
bool isConnected () const
 Tests connection to a flight controller.
bool isStatusActive (const std::string &status_name)
 Queries the flight controller to see if a status is active.
bool isStatusFailsafe ()
 Queries the flight controller to see if the FAILSAFE status is active.
bool reboot ()
 Starts message to flight controller signalling that it should reboot. Will result in the serial device disappearing if using a direct USB connection to the board.
bool saveSettings ()
 Sends message to flight controller to save all settings.
bool sendMessage (msp::Message &message, const double timeout=0)
 Sends a message to the flight controller.
void setControlSource (const ControlSource source)
 Sets which instruction source the flight controller should listen to. Also starts periodic MSP control message if MSP is selected.
void setFlightMode (const FlightMode mode)
 Sets data structure with all flags governing flight mode.
void setLoggingLevel (const msp::client::LoggingLevel &level)
 Set the verbosity of the output.
bool setMotors (const std::array< uint16_t, msp::msg::N_MOTOR > &motor_values)
 Directly sets motor values using SetMotor message.
bool setRc (const uint16_t roll, const uint16_t pitch, const uint16_t yaw, const uint16_t throttle, const uint16_t aux1=1000, const uint16_t aux2=1000, const uint16_t aux3=1000, const uint16_t aux4=1000, const std::vector< uint16_t > auxs=std::vector< uint16_t >())
 Set RC channels in order: roll, pitch, yaw, throttle by using channel mapping.
bool setRc (const std::vector< uint16_t > channels)
 Set RC channels in raw order as it is interpreted by the FC.
void setRPYT (std::array< double, 4 > &&rpyt)
 Sets roll, pitch, yaw, and throttle values. They are sent immediately and stored for resending if automatic MSP control is enabled.
template<typename T , typename C , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr
< msp::client::SubscriptionBase
subscribe (void(C::*callback)(const T &), C *context, const double tp=0.0)
 Register callback function that is called when type is received.
template<typename T , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr
< msp::client::SubscriptionBase
subscribe (const std::function< void(const T &)> &callback, const double tp=0.0)
 Register callback function that is called when type is received.
int updateFeatures (const std::set< std::string > &add=std::set< std::string >(), const std::set< std::string > &remove=std::set< std::string >())
 Enable and disable features on the FC To apply updates, changes will be written to the EEPROM and the FC will reboot.
 ~FlightController ()
 ~FlightController Destructor

Private Attributes

std::string board_name_
std::map< std::string, size_t > box_name_ids_
std::set< msp::msg::Capabilitycapabilities_
std::array< uint8_t,
msp::msg::MAX_MAPPABLE_RX_INPUTS
channel_map_
msp::client::Client client_
ControlSource control_source_
FlightMode flight_mode_
msp::FirmwareVariant fw_variant_
msp::PeriodicTimer msp_timer_
std::mutex msp_updates_mutex
int msp_version_
std::array< double, 4 > rpyt_
std::set< msp::msg::Sensorsensors_

Detailed Description

Definition at line 13 of file FlightController.hpp.


Constructor & Destructor Documentation

FlightController Constructor.

Definition at line 6 of file FlightController.cpp.

~FlightController Destructor

Definition at line 11 of file FlightController.cpp.


Member Function Documentation

bool fcu::FlightController::connect ( const std::string &  device,
const size_t  baudrate = 115200,
const double &  timeout = 0.0,
const bool  print_info = false 
)

Connects to a physical flight controller, which includes connecting the internal Client object and querying the flight controller for information necessary to configure the internal state to match the capabiliites of the flight controller.

Parameters:
timeoutTimeout passed to each internal operation (seconds)
Returns:
True on success

Definition at line 13 of file FlightController.cpp.

Stops MSP control if active, and disconnects the internal Client object.

Returns:
True on success

Definition at line 81 of file FlightController.cpp.

Method used to generate the Rc message sent to the flight controller.

Definition at line 142 of file FlightController.cpp.

std::string fcu::FlightController::getBoardName ( ) const

Queries the currently set board name.

Returns:
std::String of the board name

Definition at line 195 of file FlightController.cpp.

const std::map<std::string, size_t>& fcu::FlightController::getBoxNames ( ) const [inline]

Gets the information collected by the initBoxes() method.

Returns:
Reference to the internal mapping of strings to box IDs

Definition at line 224 of file FlightController.hpp.

Queries the currently active control source.

Returns:
ControlSource object matching current control source

Definition at line 123 of file FlightController.cpp.

Queries data structure with all flags governing flight mode.

Returns:
FlightMode object matchhing current flight mode flags

Definition at line 97 of file FlightController.cpp.

Queries the currently set firmware variant (Cleanflight, Betaflight, etc.)

Returns:
msp::FirmwareVariant enum matching the current firmware

Definition at line 189 of file FlightController.cpp.

Queries the currently set protocol (MSPv1 or MSPv2)

Returns:
integer matching the protocol version

Definition at line 193 of file FlightController.cpp.

Get pointer to subscription.

Parameters:
idMessage ID
Returns:
Pointer to subscription

Definition at line 199 of file FlightController.hpp.

bool fcu::FlightController::hasAccelerometer ( ) const [inline]

Queries for the presence of an accelerometer.

Returns:
True if there is an accelerometer

Definition at line 270 of file FlightController.hpp.

bool fcu::FlightController::hasBarometer ( ) const [inline]

Queries for the presence of a barometer.

Returns:
True if there is a barometer

Definition at line 278 of file FlightController.hpp.

bool fcu::FlightController::hasBind ( ) const [inline]

Queries for the presence of the BIND capability.

Returns:
True if the BIND capaibility is present

Definition at line 241 of file FlightController.hpp.

bool fcu::FlightController::hasCapability ( const msp::msg::Capability cap) const [inline]

Queries the cached flight controller information to see if a particular capability is present.

Returns:
True if the sensor is present

Definition at line 233 of file FlightController.hpp.

bool fcu::FlightController::hasDynBal ( ) const [inline]

Queries for the presence of the DYNBAL capability.

Returns:
True if the DYNBAL capaibility is present

Definition at line 247 of file FlightController.hpp.

bool fcu::FlightController::hasFlap ( ) const [inline]

Queries for the presence of the FLAP capability.

Returns:
True if the FLAP capaibility is present

Definition at line 255 of file FlightController.hpp.

bool fcu::FlightController::hasGPS ( ) const [inline]

Queries for the presence of a GPS.

Returns:
True if there is a GPS

Definition at line 292 of file FlightController.hpp.

bool fcu::FlightController::hasMagnetometer ( ) const [inline]

Queries for the presence of a magentometer.

Returns:
True if there is a magentometer

Definition at line 284 of file FlightController.hpp.

bool fcu::FlightController::hasSensor ( const msp::msg::Sensor sensor) const [inline]

Queries the cached flight controller information to see if a particular sensor is present.

Returns:
True if the sensor is present

Definition at line 262 of file FlightController.hpp.

bool fcu::FlightController::hasSonar ( ) const [inline]

Queries for the presence of a sonar.

Returns:
True if there is a sonar

Definition at line 298 of file FlightController.hpp.

bool fcu::FlightController::hasSubscription ( const msp::ID id) const [inline]

Check if message ID is subscribed.

Parameters:
idMessage ID
Returns:
True if there is already a subscription

Definition at line 190 of file FlightController.hpp.

Queries the flight controller for Box (flight mode) information.

Definition at line 197 of file FlightController.cpp.

bool fcu::FlightController::isArmed ( ) [inline]

Queries the flight controller to see if the ARM status is active. Not to be confused with armSet(), which queries whether the flight controller has been instructued to turn on the ARM status.

Returns:
True if the ARM status is active

Definition at line 312 of file FlightController.hpp.

Tests connection to a flight controller.

Returns:
True if connected

Definition at line 83 of file FlightController.cpp.

bool fcu::FlightController::isStatusActive ( const std::string &  status_name)

Queries the flight controller to see if a status is active.

Returns:
True if status if active

Definition at line 223 of file FlightController.cpp.

Queries the flight controller to see if the FAILSAFE status is active.

Returns:
True if the FAILSAFE status is active

Definition at line 319 of file FlightController.hpp.

Starts message to flight controller signalling that it should reboot. Will result in the serial device disappearing if using a direct USB connection to the board.

Definition at line 184 of file FlightController.cpp.

Sends message to flight controller to save all settings.

Definition at line 179 of file FlightController.cpp.

bool fcu::FlightController::sendMessage ( msp::Message message,
const double  timeout = 0 
) [inline]

Sends a message to the flight controller.

Parameters:
messageReference to a Message-derived object
timeoutNumber of seconds to wait for response. Default value of 0 means no timeout.
Returns:
True on success

Definition at line 211 of file FlightController.hpp.

Sets which instruction source the flight controller should listen to. Also starts periodic MSP control message if MSP is selected.

Parameters:
modeFlightMode object

Definition at line 99 of file FlightController.cpp.

Sets data structure with all flags governing flight mode.

Parameters:
modeFlightMode object

Definition at line 89 of file FlightController.cpp.

Set the verbosity of the output.

Parameters:
levelLoggingLevel matching the desired amount of output (default to WARNING)

Definition at line 85 of file FlightController.cpp.

bool fcu::FlightController::setMotors ( const std::array< uint16_t, msp::msg::N_MOTOR > &  motor_values)

Directly sets motor values using SetMotor message.

Returns:
True on successful message delivery

Definition at line 270 of file FlightController.cpp.

bool fcu::FlightController::setRc ( const uint16_t  roll,
const uint16_t  pitch,
const uint16_t  yaw,
const uint16_t  throttle,
const uint16_t  aux1 = 1000,
const uint16_t  aux2 = 1000,
const uint16_t  aux3 = 1000,
const uint16_t  aux4 = 1000,
const std::vector< uint16_t >  auxs = std::vector<uint16_t>() 
)

Set RC channels in order: roll, pitch, yaw, throttle by using channel mapping.

Parameters:
roll
pitch
yaw
throttle
aux1
aux2
aux3
aux4
auxs
Returns:

Definition at line 239 of file FlightController.cpp.

bool fcu::FlightController::setRc ( const std::vector< uint16_t >  channels)

Set RC channels in raw order as it is interpreted by the FC.

Parameters:
channelslist of channel values (1000-2000)
Returns:

Definition at line 264 of file FlightController.cpp.

void fcu::FlightController::setRPYT ( std::array< double, 4 > &&  rpyt)

Sets roll, pitch, yaw, and throttle values. They are sent immediately and stored for resending if automatic MSP control is enabled.

Parameters:
rpytAn array of doubles representing roll, pitch, yaw, and throttle in that order. Values are expected to be in the range -1.0 to +1.0, mapping to 1000us to 2000us pulse widths.

Definition at line 134 of file FlightController.cpp.

template<typename T , typename C , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr<msp::client::SubscriptionBase> fcu::FlightController::subscribe ( void(C::*)(const T &)  callback,
C *  context,
const double  tp = 0.0 
) [inline]

Register callback function that is called when type is received.

Parameters:
callbackPointer to callback function (class method)
contextObject with callback method
tpPeriod of timer that will send subscribed requests (in seconds), by default this is 0 and requests are not sent periodically
Returns:
Pointer to subscription that is added to internal list

Definition at line 165 of file FlightController.hpp.

template<typename T , class = typename std::enable_if< std::is_base_of<msp::Message, T>::value>::type>
std::shared_ptr<msp::client::SubscriptionBase> fcu::FlightController::subscribe ( const std::function< void(const T &)> &  callback,
const double  tp = 0.0 
) [inline]

Register callback function that is called when type is received.

Parameters:
callbackFunction to be called (e.g. lambda, class method, function pointer)
tpPeriod of timer that will send subscribed requests (in seconds), by default this is 0 and requests are not sent periodically
Returns:
Pointer to subscription that is added to internal list

Definition at line 180 of file FlightController.hpp.

int fcu::FlightController::updateFeatures ( const std::set< std::string > &  add = std::set<std::string>(),
const std::set< std::string > &  remove = std::set<std::string>() 
)

Enable and disable features on the FC To apply updates, changes will be written to the EEPROM and the FC will reboot.

Parameters:
addset of features to enable
removeset of features to disable
Returns:
1 if features have been changed
0 if no changes have been applied
-1 on failure

Definition at line 277 of file FlightController.cpp.


Member Data Documentation

std::string fcu::FlightController::board_name_ [private]

Definition at line 346 of file FlightController.hpp.

std::map<std::string, size_t> fcu::FlightController::box_name_ids_ [private]

Definition at line 349 of file FlightController.hpp.

Definition at line 352 of file FlightController.hpp.

Definition at line 351 of file FlightController.hpp.

Definition at line 343 of file FlightController.hpp.

Definition at line 360 of file FlightController.hpp.

Definition at line 356 of file FlightController.hpp.

Definition at line 347 of file FlightController.hpp.

Definition at line 362 of file FlightController.hpp.

Definition at line 358 of file FlightController.hpp.

Definition at line 348 of file FlightController.hpp.

std::array<double, 4> fcu::FlightController::rpyt_ [private]

Definition at line 355 of file FlightController.hpp.

Definition at line 350 of file FlightController.hpp.


The documentation for this class was generated from the following files:


msp
Author(s): Christian Rauch
autogenerated on Thu Jun 20 2019 19:40:38