FlightController.hpp
Go to the documentation of this file.
1 #ifndef FLIGHTCONTROLLER_HPP
2 #define FLIGHTCONTROLLER_HPP
3 
4 #include "Client.hpp"
5 #include "FlightMode.hpp"
6 #include "PeriodicTimer.hpp"
7 #include "msp_msg.hpp"
8 
9 namespace fcu {
10 
11 enum class ControlSource { NONE, SBUS, MSP, OTHER };
12 
14 public:
19 
24 
33  bool connect(const std::string &device, const size_t baudrate = 115200,
34  const double &timeout = 0.0, const bool print_info = false);
35 
41  bool disconnect();
42 
47  bool isConnected() const;
48 
53  void setFlightMode(const FlightMode mode);
54 
59  FlightMode getFlightMode() const;
60 
66  void setControlSource(const ControlSource source);
67 
72  ControlSource getControlSource();
73 
81  void setRPYT(std::array<double, 4> &&rpyt);
82 
87  void generateMSP();
88 
92  bool saveSettings();
93 
99  bool reboot();
100 
106  msp::FirmwareVariant getFwVariant() const;
107 
112  int getProtocolVersion() const;
113 
118  std::string getBoardName() const;
119 
125  void setLoggingLevel(const msp::client::LoggingLevel &level);
126 
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>());
146 
152  bool setRc(const std::vector<uint16_t> channels);
153 
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);
168  }
169 
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);
183  }
184 
190  bool hasSubscription(const msp::ID &id) const {
191  return client_.hasSubscription(id);
192  }
193 
199  std::shared_ptr<msp::client::SubscriptionBase> getSubscription(
200  const msp::ID &id) {
201  return client_.getSubscription(id);
202  }
203 
211  bool sendMessage(msp::Message &message, const double timeout = 0) {
212  return client_.sendMessage(message, timeout);
213  }
214 
218  void initBoxes();
219 
224  const std::map<std::string, size_t> &getBoxNames() const {
225  return box_name_ids_;
226  }
227 
233  bool hasCapability(const msp::msg::Capability &cap) const {
234  return capabilities_.count(cap);
235  }
236 
241  bool hasBind() const { return hasCapability(msp::msg::Capability::BIND); }
242 
247  bool hasDynBal() const {
248  return hasCapability(msp::msg::Capability::DYNBAL);
249  }
250 
255  bool hasFlap() const { return hasCapability(msp::msg::Capability::FLAP); }
256 
262  bool hasSensor(const msp::msg::Sensor &sensor) const {
263  return sensors_.count(sensor);
264  }
265 
270  bool hasAccelerometer() const {
271  return hasSensor(msp::msg::Sensor::Accelerometer);
272  }
273 
278  bool hasBarometer() const { return hasSensor(msp::msg::Sensor::Barometer); }
279 
284  bool hasMagnetometer() const {
285  return hasSensor(msp::msg::Sensor::Magnetometer);
286  }
287 
292  bool hasGPS() const { return hasSensor(msp::msg::Sensor::GPS); }
293 
298  bool hasSonar() const { return hasSensor(msp::msg::Sensor::Sonar); }
299 
306  bool isStatusActive(const std::string &status_name,
307  const double &timeout = 0);
308 
315  bool isArmed() { return isStatusActive("ARM", 0.1); }
316 
322  bool isStatusFailsafe() { return isStatusActive("FAILSAFE"); }
323 
328  bool setMotors(const std::array<uint16_t, msp::msg::N_MOTOR> &motor_values);
329 
340  int updateFeatures(
341  const std::set<std::string> &add = std::set<std::string>(),
342  const std::set<std::string> &remove = std::set<std::string>());
343 
344 private:
345  // Client instance for managing the actual comms with the flight controller
347 
348  // parameters updated by the connect method to cache flight controller info
349  std::string board_name_;
352  std::map<std::string, size_t> box_name_ids_;
353  std::set<msp::msg::Sensor> sensors_;
354  std::array<uint8_t, msp::msg::MAX_MAPPABLE_RX_INPUTS> channel_map_;
355  std::set<msp::msg::Capability> capabilities_;
356 
357  // parameters updated by the user, and consumed by MSP control messages
358  std::array<double, 4> rpyt_;
360 
361  std::mutex msp_updates_mutex;
362 
364 
366 };
367 
368 } // namespace fcu
369 
370 #endif // FLIGHTCONTROLLER_HPP
msp::FirmwareVariant fw_variant_
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()...
ID
Definition: msp_msg.hpp:30
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::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_


msp
Author(s): Christian Rauch
autogenerated on Tue Oct 6 2020 03:38:57