1 #ifndef FLIGHTCONTROLLER_HPP 2 #define FLIGHTCONTROLLER_HPP 33 bool connect(
const std::string &device,
const size_t baudrate = 115200,
34 const double &timeout = 0.0,
const bool print_info =
false);
47 bool isConnected()
const;
81 void setRPYT(std::array<double, 4> &&rpyt);
112 int getProtocolVersion()
const;
118 std::string getBoardName()
const;
141 bool setRc(
const uint16_t roll,
const uint16_t pitch,
const uint16_t yaw,
142 const uint16_t throttle,
const uint16_t aux1 = 1000,
143 const uint16_t aux2 = 1000,
const uint16_t aux3 = 1000,
144 const uint16_t aux4 = 1000,
145 const std::vector<uint16_t> auxs = std::vector<uint16_t>());
152 bool setRc(
const std::vector<uint16_t> channels);
162 template <
typename T,
typename C,
163 class =
typename std::enable_if<
164 std::is_base_of<msp::Message, T>::value>::type>
165 std::shared_ptr<msp::client::SubscriptionBase>
subscribe(
166 void (C::*callback)(
const T &), C *context,
const double tp = 0.0) {
167 return client_.subscribe(callback, context, tp);
178 template <
typename T,
class =
typename std::enable_if<
179 std::is_base_of<msp::Message, T>::value>::type>
180 std::shared_ptr<msp::client::SubscriptionBase>
subscribe(
181 const std::function<
void(
const T &)> &callback,
const double tp = 0.0) {
182 return client_.subscribe(callback, tp);
191 return client_.hasSubscription(
id);
201 return client_.getSubscription(
id);
212 return client_.sendMessage(message, timeout);
225 return box_name_ids_;
234 return capabilities_.count(cap);
263 return sensors_.count(sensor);
306 bool isStatusActive(
const std::string &status_name,
307 const double &timeout = 0);
315 bool isArmed() {
return isStatusActive(
"ARM", 0.1); }
328 bool setMotors(
const std::array<uint16_t, msp::msg::N_MOTOR> &motor_values);
341 const std::set<std::string> &add = std::set<std::string>(),
342 const std::set<std::string> &
remove = std::set<std::string>());
370 #endif // FLIGHTCONTROLLER_HPP msp::FirmwareVariant fw_variant_
ControlSource control_source_
bool isStatusFailsafe()
Queries the flight controller to see if the FAILSAFE status is active.
std::array< uint8_t, msp::msg::MAX_MAPPABLE_RX_INPUTS > channel_map_
bool hasMagnetometer() const
Queries for the presence of a magentometer.
const std::map< std::string, size_t > & getBoxNames() const
Gets the information collected by the initBoxes() method.
bool hasSonar() const
Queries for the presence of a sonar.
std::set< msp::msg::Capability > capabilities_
msp::client::Client client_
std::array< double, 4 > rpyt_
bool isArmed()
Queries the flight controller to see if the ARM status is active. Not to be confused with armSet()...
bool hasSubscription(const msp::ID &id) const
Check if message ID is subscribed.
FirmwareVariant
Enum of firmware variants.
bool hasCapability(const msp::msg::Capability &cap) const
Queries the cached flight controller information to see if a particular capability is present...
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.
bool hasAccelerometer() const
Queries for the presence of an accelerometer.
bool sendMessage(msp::Message &message, const double timeout=0)
Sends a message to the flight controller.
bool hasBind() const
Queries for the presence of the BIND capability.
bool hasBarometer() const
Queries for the presence of a barometer.
std::set< msp::msg::Sensor > sensors_
std::shared_ptr< msp::client::SubscriptionBase > getSubscription(const msp::ID &id)
Get pointer to subscription.
bool hasSensor(const msp::msg::Sensor &sensor) const
Queries the cached flight controller information to see if a particular sensor is present...
bool hasDynBal() const
Queries for the presence of the DYNBAL capability.
std::mutex msp_updates_mutex
std::map< std::string, size_t > box_name_ids_
bool hasFlap() const
Queries for the presence of the FLAP capability.
bool hasGPS() const
Queries for the presence of a GPS.
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.
msp::PeriodicTimer msp_timer_