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

#include <FlightController.hpp>

List of all members.

Public Member Functions

bool arm (const bool arm)
 arm arm or disarm FC
bool arm_block ()
 arm_block attempt to arm and wait for status feedback, e.g. this method will block until the FC is able to aim
bool disarm_block ()
 disarm_block attempt to disarm and wait for status feedback
bool enableRxMSP ()
 enableRxMSP enable the "RX_MSP" feature The features "RX_MSP", "RX_PARALLEL_PWM", "RX_PPM" and "RX_SERIAL" are mutually exclusive. Hence one of the features "RX_PARALLEL_PWM", "RX_PPM" or "RX_SERIAL" will be disabled if active.
 FlightController (const std::string &device, const uint baudrate=115200)
std::map< std::string, uint > & getBoxNames ()
msp::client::SubscriptionBasegetSubscription (const msp::ID &id)
 getSubscription get pointer to subscription
bool hasAccelerometer () const
bool hasBarometer () const
bool hasBind () const
bool hasCapability (const msp::msg::Capability &cap) const
bool hasDynBal () const
bool hasFlap () const
bool hasGPS () const
bool hasMagnetometer () const
bool hasSensor (const msp::msg::Sensor &sensor) const
bool hasSonar () const
bool hasSubscription (const msp::ID &id)
 hasSubscription check if message ID is subscribed
void initBoxes ()
void initialise ()
bool isArmed ()
bool isFirmware (const FirmwareType firmware_type)
 isFirmware determine firmware type (e.g. to distiguish accepted messages)
bool isFirmwareCleanflight ()
bool isFirmwareMultiWii ()
bool isStatusActive (const std::string &status_name)
bool isStatusFailsafe ()
bool reboot ()
bool request (msp::Request &request, const double timeout=0)
bool request_raw (const uint8_t id, msp::ByteVector &data, const double timeout=0)
bool respond (const msp::Response &response, const bool wait_ack=true)
bool respond_raw (const uint8_t id, msp::ByteVector &data, const bool wait_ack=true)
bool sendRequest (const uint8_t id)
 sendRequest send request with ID
bool setMotors (const std::array< uint16_t, msp::msg::N_MOTOR > &motor_values)
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 >())
 setRc set RC channels in order: roll, pitch, yaw, throttle by using channel mapping
bool setRc (const std::vector< uint16_t > channels)
 setRc set RC channels in raw order as it is interpreted by the FC
template<typename T , typename C >
msp::client::SubscriptionBasesubscribe (void(C::*callback)(const T &), C *context, const double tp=0.0)
 subscribe 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 >())
 updateFeatures enable and disable features on the FC To apply updates, changes will be written to the EEPROM and the FC will reboot.
void waitForConnection ()
bool writeEEPROM ()
 ~FlightController ()

Private Attributes

std::map< std::string, uintbox_name_ids
std::vector< uint8_t > channel_map
msp::client::Client client
FirmwareType firmware
msp::msg::Ident ident
std::set< msp::msg::Sensorsensors

Static Private Attributes

static const uint8_t MAX_MAPPABLE_RX_INPUTS = 8

Detailed Description

Definition at line 16 of file FlightController.hpp.


Constructor & Destructor Documentation

fcu::FlightController::FlightController ( const std::string &  device,
const uint  baudrate = 115200 
)

Definition at line 7 of file FlightController.cpp.

Definition at line 12 of file FlightController.cpp.


Member Function Documentation

bool fcu::FlightController::arm ( const bool  arm)

arm arm or disarm FC

Parameters:
armtrue: will arm FC, false: will disarm FC
Returns:
true on success

Definition at line 158 of file FlightController.cpp.

arm_block attempt to arm and wait for status feedback, e.g. this method will block until the FC is able to aim

Returns:

Definition at line 169 of file FlightController.cpp.

disarm_block attempt to disarm and wait for status feedback

Returns:

Definition at line 178 of file FlightController.cpp.

enableRxMSP enable the "RX_MSP" feature The features "RX_MSP", "RX_PARALLEL_PWM", "RX_PPM" and "RX_SERIAL" are mutually exclusive. Hence one of the features "RX_PARALLEL_PWM", "RX_PPM" or "RX_SERIAL" will be disabled if active.

Returns:
true on success

Definition at line 213 of file FlightController.hpp.

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

Definition at line 97 of file FlightController.hpp.

getSubscription get pointer to subscription

Parameters:
idmessage ID
Returns:
pointer to subscription

Definition at line 65 of file FlightController.hpp.

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

Definition at line 121 of file FlightController.hpp.

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

Definition at line 125 of file FlightController.hpp.

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

Definition at line 105 of file FlightController.hpp.

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

Definition at line 101 of file FlightController.hpp.

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

Definition at line 109 of file FlightController.hpp.

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

Definition at line 113 of file FlightController.hpp.

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

Definition at line 133 of file FlightController.hpp.

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

Definition at line 129 of file FlightController.hpp.

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

Definition at line 117 of file FlightController.hpp.

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

Definition at line 137 of file FlightController.hpp.

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

hasSubscription check if message ID is subscribed

Parameters:
idmessage ID
Returns:
true if there is already a subscription
false if ID is not subscribed

Definition at line 56 of file FlightController.hpp.

Definition at line 67 of file FlightController.cpp.

Definition at line 23 of file FlightController.cpp.

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

Definition at line 143 of file FlightController.hpp.

bool fcu::FlightController::isFirmware ( const FirmwareType  firmware_type)

isFirmware determine firmware type (e.g. to distiguish accepted messages)

Parameters:
firmware_typetype of firmware (enum FirmwareType)
Returns:
true if firmware is firmware_type
false if firmware is not firmware_type

Definition at line 63 of file FlightController.cpp.

Definition at line 36 of file FlightController.hpp.

Definition at line 34 of file FlightController.hpp.

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

Definition at line 96 of file FlightController.cpp.

Definition at line 145 of file FlightController.hpp.

Definition at line 223 of file FlightController.cpp.

bool fcu::FlightController::request ( msp::Request request,
const double  timeout = 0 
) [inline]

Definition at line 79 of file FlightController.hpp.

bool fcu::FlightController::request_raw ( const uint8_t  id,
msp::ByteVector data,
const double  timeout = 0 
) [inline]

Definition at line 83 of file FlightController.hpp.

bool fcu::FlightController::respond ( const msp::Response response,
const bool  wait_ack = true 
) [inline]

Definition at line 87 of file FlightController.hpp.

bool fcu::FlightController::respond_raw ( const uint8_t  id,
msp::ByteVector data,
const bool  wait_ack = true 
) [inline]

Definition at line 91 of file FlightController.hpp.

bool fcu::FlightController::sendRequest ( const uint8_t  id) [inline]

sendRequest send request with ID

Parameters:
idmessage ID of request
Returns:
true on success
false on failure

Definition at line 75 of file FlightController.hpp.

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

Definition at line 146 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>() 
)

setRc 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 109 of file FlightController.cpp.

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

setRc set RC channels in raw order as it is interpreted by the FC

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

Definition at line 140 of file FlightController.cpp.

template<typename T , typename C >
msp::client::SubscriptionBase* fcu::FlightController::subscribe ( void(C::*)(const T &)  callback,
C *  context,
const double  tp = 0.0 
) [inline]

subscribe register callback function that is called when type is received

Parameters:
callbackpointer to callback function (class method)
contextclass with callback method
tpperiod at a timer 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 46 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>() 
)

updateFeatures 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 187 of file FlightController.cpp.

Definition at line 16 of file FlightController.cpp.

Definition at line 227 of file FlightController.cpp.


Member Data Documentation

std::map<std::string, uint> fcu::FlightController::box_name_ids [private]

Definition at line 230 of file FlightController.hpp.

std::vector<uint8_t> fcu::FlightController::channel_map [private]

Definition at line 238 of file FlightController.hpp.

Definition at line 228 of file FlightController.hpp.

Definition at line 236 of file FlightController.hpp.

Definition at line 232 of file FlightController.hpp.

const uint8_t fcu::FlightController::MAX_MAPPABLE_RX_INPUTS = 8 [static, private]

Definition at line 226 of file FlightController.hpp.

Definition at line 234 of file FlightController.hpp.


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


msp
Author(s): Christian Rauch
autogenerated on Mon Oct 9 2017 03:02:14