#include <FlightController.hpp>
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. More... | |
bool | disconnect () |
Stops MSP control if active, and disconnects the internal Client object. More... | |
FlightController () | |
FlightController Constructor. More... | |
void | generateMSP () |
Method used to generate the Rc message sent to the flight controller. More... | |
std::string | getBoardName () const |
Queries the currently set board name. More... | |
const std::map< std::string, size_t > & | getBoxNames () const |
Gets the information collected by the initBoxes() method. More... | |
ControlSource | getControlSource () |
Queries the currently active control source. More... | |
FlightMode | getFlightMode () const |
Queries data structure with all flags governing flight mode. More... | |
msp::FirmwareVariant | getFwVariant () const |
Queries the currently set firmware variant (Cleanflight, Betaflight, etc.) More... | |
int | getProtocolVersion () const |
Queries the currently set protocol (MSPv1 or MSPv2) More... | |
std::shared_ptr< msp::client::SubscriptionBase > | getSubscription (const msp::ID &id) |
Get pointer to subscription. More... | |
bool | hasAccelerometer () const |
Queries for the presence of an accelerometer. More... | |
bool | hasBarometer () const |
Queries for the presence of a barometer. More... | |
bool | hasBind () const |
Queries for the presence of the BIND capability. More... | |
bool | hasCapability (const msp::msg::Capability &cap) const |
Queries the cached flight controller information to see if a particular capability is present. More... | |
bool | hasDynBal () const |
Queries for the presence of the DYNBAL capability. More... | |
bool | hasFlap () const |
Queries for the presence of the FLAP capability. More... | |
bool | hasGPS () const |
Queries for the presence of a GPS. More... | |
bool | hasMagnetometer () const |
Queries for the presence of a magentometer. More... | |
bool | hasSensor (const msp::msg::Sensor &sensor) const |
Queries the cached flight controller information to see if a particular sensor is present. More... | |
bool | hasSonar () const |
Queries for the presence of a sonar. More... | |
bool | hasSubscription (const msp::ID &id) const |
Check if message ID is subscribed. More... | |
void | initBoxes () |
Queries the flight controller for Box (flight mode) information. More... | |
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. More... | |
bool | isConnected () const |
Tests connection to a flight controller. More... | |
bool | isStatusActive (const std::string &status_name, const double &timeout=0) |
Queries the flight controller to see if a status is active. More... | |
bool | isStatusFailsafe () |
Queries the flight controller to see if the FAILSAFE status is active. More... | |
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. More... | |
bool | saveSettings () |
Sends message to flight controller to save all settings. More... | |
bool | sendMessage (msp::Message &message, const double timeout=0) |
Sends a message to the flight controller. More... | |
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. More... | |
void | setFlightMode (const FlightMode mode) |
Sets data structure with all flags governing flight mode. More... | |
void | setLoggingLevel (const msp::client::LoggingLevel &level) |
Set the verbosity of the output. More... | |
bool | setMotors (const std::array< uint16_t, msp::msg::N_MOTOR > &motor_values) |
Directly sets motor values using SetMotor message. More... | |
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. More... | |
bool | setRc (const std::vector< uint16_t > channels) |
Set RC channels in raw order as it is interpreted by the FC. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
~FlightController () | |
~FlightController Destructor More... | |
Private Attributes | |
std::string | board_name_ |
std::map< std::string, size_t > | box_name_ids_ |
std::set< msp::msg::Capability > | capabilities_ |
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::Sensor > | sensors_ |
Definition at line 13 of file FlightController.hpp.
fcu::FlightController::FlightController | ( | ) |
FlightController Constructor.
Definition at line 6 of file FlightController.cpp.
fcu::FlightController::~FlightController | ( | ) |
~FlightController Destructor
Definition at line 11 of file FlightController.cpp.
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.
timeout | Timeout passed to each internal operation (seconds) |
Definition at line 13 of file FlightController.cpp.
bool fcu::FlightController::disconnect | ( | ) |
Stops MSP control if active, and disconnects the internal Client object.
Definition at line 81 of file FlightController.cpp.
void fcu::FlightController::generateMSP | ( | ) |
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.
Definition at line 195 of file FlightController.cpp.
|
inline |
Gets the information collected by the initBoxes() method.
Definition at line 224 of file FlightController.hpp.
ControlSource fcu::FlightController::getControlSource | ( | ) |
Queries the currently active control source.
Definition at line 123 of file FlightController.cpp.
FlightMode fcu::FlightController::getFlightMode | ( | ) | const |
Queries data structure with all flags governing flight mode.
Definition at line 97 of file FlightController.cpp.
msp::FirmwareVariant fcu::FlightController::getFwVariant | ( | ) | const |
Queries the currently set firmware variant (Cleanflight, Betaflight, etc.)
Definition at line 189 of file FlightController.cpp.
int fcu::FlightController::getProtocolVersion | ( | ) | const |
Queries the currently set protocol (MSPv1 or MSPv2)
Definition at line 193 of file FlightController.cpp.
|
inline |
Get pointer to subscription.
id | Message ID |
Definition at line 199 of file FlightController.hpp.
|
inline |
Queries for the presence of an accelerometer.
Definition at line 270 of file FlightController.hpp.
|
inline |
Queries for the presence of a barometer.
Definition at line 278 of file FlightController.hpp.
|
inline |
Queries for the presence of the BIND capability.
Definition at line 241 of file FlightController.hpp.
|
inline |
Queries the cached flight controller information to see if a particular capability is present.
Definition at line 233 of file FlightController.hpp.
|
inline |
Queries for the presence of the DYNBAL capability.
Definition at line 247 of file FlightController.hpp.
|
inline |
Queries for the presence of the FLAP capability.
Definition at line 255 of file FlightController.hpp.
|
inline |
Queries for the presence of a GPS.
Definition at line 292 of file FlightController.hpp.
|
inline |
Queries for the presence of a magentometer.
Definition at line 284 of file FlightController.hpp.
|
inline |
Queries the cached flight controller information to see if a particular sensor is present.
Definition at line 262 of file FlightController.hpp.
|
inline |
Queries for the presence of a sonar.
Definition at line 298 of file FlightController.hpp.
|
inline |
Check if message ID is subscribed.
id | Message ID |
Definition at line 190 of file FlightController.hpp.
void fcu::FlightController::initBoxes | ( | ) |
Queries the flight controller for Box (flight mode) information.
Definition at line 197 of file FlightController.cpp.
|
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.
Definition at line 315 of file FlightController.hpp.
bool fcu::FlightController::isConnected | ( | ) | const |
Tests connection to a flight controller.
Definition at line 83 of file FlightController.cpp.
bool fcu::FlightController::isStatusActive | ( | const std::string & | status_name, |
const double & | timeout = 0 |
||
) |
Queries the flight controller to see if a status is active.
status_name | of boxitems |
timeout | Maximum amount of time to block waiting for a response. |
Definition at line 223 of file FlightController.cpp.
|
inline |
Queries the flight controller to see if the FAILSAFE status is active.
Definition at line 322 of file FlightController.hpp.
bool fcu::FlightController::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.
Definition at line 184 of file FlightController.cpp.
bool fcu::FlightController::saveSettings | ( | ) |
Sends message to flight controller to save all settings.
Definition at line 179 of file FlightController.cpp.
|
inline |
Sends a message to the flight controller.
message | Reference to a Message-derived object |
timeout | Number of seconds to wait for response. Default value of 0 means no timeout. |
Definition at line 211 of file FlightController.hpp.
void fcu::FlightController::setControlSource | ( | const ControlSource | source | ) |
Sets which instruction source the flight controller should listen to. Also starts periodic MSP control message if MSP is selected.
mode | FlightMode object |
Definition at line 99 of file FlightController.cpp.
void fcu::FlightController::setFlightMode | ( | const FlightMode | mode | ) |
Sets data structure with all flags governing flight mode.
mode | FlightMode object |
Definition at line 89 of file FlightController.cpp.
void fcu::FlightController::setLoggingLevel | ( | const msp::client::LoggingLevel & | level | ) |
Set the verbosity of the output.
level | LoggingLevel 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.
Definition at line 271 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.
roll | |
pitch | |
yaw | |
throttle | |
aux1 | |
aux2 | |
aux3 | |
aux4 | |
auxs |
Definition at line 240 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.
channels | list of channel values (1000-2000) |
Definition at line 265 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.
rpyt | An 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.
|
inline |
Register callback function that is called when type is received.
callback | Pointer to callback function (class method) |
context | Object with callback method |
tp | Period of timer that will send subscribed requests (in seconds), by default this is 0 and requests are not sent periodically |
Definition at line 165 of file FlightController.hpp.
|
inline |
Register callback function that is called when type is received.
callback | Function to be called (e.g. lambda, class method, function pointer) |
tp | Period of timer that will send subscribed requests (in seconds), by default this is 0 and requests are not sent periodically |
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.
add | set of features to enable |
remove | set of features to disable |
Definition at line 278 of file FlightController.cpp.
|
private |
Definition at line 349 of file FlightController.hpp.
|
private |
Definition at line 352 of file FlightController.hpp.
|
private |
Definition at line 355 of file FlightController.hpp.
|
private |
Definition at line 354 of file FlightController.hpp.
|
private |
Definition at line 346 of file FlightController.hpp.
|
private |
Definition at line 363 of file FlightController.hpp.
|
private |
Definition at line 359 of file FlightController.hpp.
|
private |
Definition at line 350 of file FlightController.hpp.
|
private |
Definition at line 365 of file FlightController.hpp.
|
private |
Definition at line 361 of file FlightController.hpp.
|
private |
Definition at line 351 of file FlightController.hpp.
|
private |
Definition at line 358 of file FlightController.hpp.
|
private |
Definition at line 353 of file FlightController.hpp.