Go to the documentation of this file.00001 #include "FlightController.hpp"
00002 #include <iostream>
00003
00004 namespace fcu {
00005
00006 FlightController::FlightController() :
00007 msp_version_(1),
00008 control_source_(ControlSource::NONE),
00009 msp_timer_(std::bind(&FlightController::generateMSP, this), 0.1) {}
00010
00011 FlightController::~FlightController() { disconnect(); }
00012
00013 bool FlightController::connect(const std::string &device, const size_t baudrate,
00014 const double &timeout, const bool print_info) {
00015 if(!client_.start(device, baudrate)) return false;
00016
00017 msp::msg::FcVariant fcvar(fw_variant_);
00018 if(client_.sendMessage(fcvar, timeout)) {
00019 fw_variant_ = msp::variant_map.at(fcvar.identifier());
00020 if(print_info) std::cout << fcvar;
00021 }
00022
00023 if(fw_variant_ != msp::FirmwareVariant::MWII) {
00024 msp::msg::ApiVersion api_version(fw_variant_);
00025 if(client_.sendMessage(api_version, timeout)) {
00026 if(print_info) std::cout << api_version;
00027 msp_version_ = api_version.major();
00028 client_.setVersion(msp_version_);
00029 }
00030 }
00031
00032 if(print_info) {
00033 msp::msg::FcVersion fcver(fw_variant_);
00034 if(client_.sendMessage(fcver, timeout)) {
00035 std::cout << fcver;
00036 }
00037 }
00038
00039 msp::msg::BoardInfo boardinfo(fw_variant_);
00040 if(client_.sendMessage(boardinfo, timeout)) {
00041 if(print_info) std::cout << boardinfo;
00042 board_name_ = boardinfo.name();
00043 }
00044
00045 if(print_info) {
00046 msp::msg::BuildInfo buildinfo(fw_variant_);
00047 if(client_.sendMessage(buildinfo, timeout)) std::cout << buildinfo;
00048 }
00049
00050 msp::msg::Status status(fw_variant_);
00051 client_.sendMessage(status, timeout);
00052 if(print_info) std::cout << status;
00053 sensors_ = status.sensors;
00054
00055 msp::msg::Ident ident(fw_variant_);
00056 client_.sendMessage(ident, timeout);
00057 if(print_info) std::cout << ident;
00058 capabilities_ = ident.capabilities;
00059
00060
00061 initBoxes();
00062
00063
00064 if(getFwVariant() == msp::FirmwareVariant::MWII) {
00065
00066 for(uint8_t i(0); i < msp::msg::MAX_MAPPABLE_RX_INPUTS; ++i) {
00067 channel_map_[i] = i;
00068 }
00069 }
00070 else {
00071
00072 msp::msg::RxMap rx_map(fw_variant_);
00073 client_.sendMessage(rx_map, timeout);
00074 if(print_info) std::cout << rx_map;
00075 channel_map_ = rx_map.map;
00076 }
00077
00078 return true;
00079 }
00080
00081 bool FlightController::disconnect() { return client_.stop(); }
00082
00083 bool FlightController::isConnected() const { return client_.isConnected(); }
00084
00085 void FlightController::setLoggingLevel(const msp::client::LoggingLevel &level) {
00086 client_.setLoggingLevel(level);
00087 }
00088
00089 void FlightController::setFlightMode(FlightMode mode) {
00090 {
00091 std::lock_guard<std::mutex> lock(msp_updates_mutex);
00092 flight_mode_ = mode;
00093 }
00094 generateMSP();
00095 }
00096
00097 FlightMode FlightController::getFlightMode() const { return flight_mode_; }
00098
00099 void FlightController::setControlSource(ControlSource source) {
00100 if(source == control_source_) return;
00101
00102 msp::msg::RxConfig rxConfig(fw_variant_);
00103 if(!client_.sendMessage(rxConfig))
00104 std::cout << "client_.sendMessage(rxConfig) failed" << std::endl;
00105 std::cout << rxConfig;
00106
00107 msp::msg::SetRxConfig setRxConfig(fw_variant_);
00108 static_cast<msp::msg::RxConfigSettings &>(setRxConfig) =
00109 static_cast<msp::msg::RxConfigSettings &>(rxConfig);
00110
00111 if(source == ControlSource::SBUS) {
00112 setRxConfig.receiverType = 3;
00113 setRxConfig.serialrx_provider = 2;
00114 }
00115 else if(source == ControlSource::MSP) {
00116 setRxConfig.receiverType = 4;
00117 }
00118 client_.sendMessage(setRxConfig);
00119
00120 control_source_ = source;
00121 }
00122
00123 ControlSource FlightController::getControlSource() {
00124 msp::msg::RxConfig rxConfig(fw_variant_);
00125 client_.sendMessage(rxConfig);
00126
00127 if(rxConfig.receiverType.set() && rxConfig.receiverType() == 4)
00128 return ControlSource::MSP;
00129 else if(rxConfig.serialrx_provider() == 2)
00130 return ControlSource::SBUS;
00131 return ControlSource::OTHER;
00132 }
00133
00134 void FlightController::setRPYT(std::array<double, 4> &&rpyt) {
00135 {
00136 std::lock_guard<std::mutex> lock(msp_updates_mutex);
00137 rpyt_.swap(rpyt);
00138 }
00139 generateMSP();
00140 }
00141
00142 void FlightController::generateMSP() {
00143 std::vector<uint16_t> cmds(6, 1000);
00144
00145
00146 {
00147 std::lock_guard<std::mutex> lock(msp_updates_mutex);
00148 cmds[0] = uint16_t(rpyt_[3] * 500) + 1500;
00149 cmds[1] = uint16_t(rpyt_[0] * 500) + 1500;
00150 cmds[2] = uint16_t(rpyt_[1] * 500) + 1500;
00151 cmds[3] = uint16_t(rpyt_[2] * 500) + 1500;
00152
00153 if(!(uint32_t(flight_mode_.modifier) &
00154 uint32_t(FlightMode::MODIFIER::ARM)))
00155 cmds[4] = 1000;
00156 else if(uint32_t(flight_mode_.secondary) &
00157 uint32_t(FlightMode::SECONDARY_MODE::NAV_ALTHOLD))
00158 cmds[4] = 2000;
00159 else
00160 cmds[4] = 1500;
00161
00162 switch(flight_mode_.primary) {
00163 case FlightMode::PRIMARY_MODE::ANGLE:
00164 cmds[5] = 1000;
00165 break;
00166 case FlightMode::PRIMARY_MODE::NAV_POSHOLD:
00167 cmds[5] = 1500;
00168 break;
00169 case FlightMode::PRIMARY_MODE::NAV_RTH:
00170 cmds[5] = 2000;
00171 break;
00172 default:
00173 break;
00174 }
00175 }
00176 setRc(cmds);
00177 }
00178
00179 bool FlightController::saveSettings() {
00180 msp::msg::WriteEEPROM writeEEPROM(fw_variant_);
00181 return client_.sendMessage(writeEEPROM);
00182 }
00183
00184 bool FlightController::reboot() {
00185 msp::msg::Reboot reboot(fw_variant_);
00186 return client_.sendMessage(reboot);
00187 }
00188
00189 msp::FirmwareVariant FlightController::getFwVariant() const {
00190 return fw_variant_;
00191 }
00192
00193 int FlightController::getProtocolVersion() const { return msp_version_; }
00194
00195 std::string FlightController::getBoardName() const { return board_name_; }
00196
00197 void FlightController::initBoxes() {
00198
00199 msp::msg::BoxNames box_names(fw_variant_);
00200 if(!client_.sendMessage(box_names))
00201 throw std::runtime_error("Cannot get BoxNames!");
00202
00203
00204 msp::msg::BoxIds box_ids(fw_variant_);
00205 if(!client_.sendMessage(box_ids))
00206 throw std::runtime_error("Cannot get BoxIds!");
00207 assert(box_names.box_names.size() == box_ids.box_ids.size());
00208
00209 box_name_ids_.clear();
00210 for(size_t ibox(0); ibox < box_names.box_names.size(); ibox++) {
00211 if(getFwVariant() == msp::FirmwareVariant::CLFL) {
00212
00213
00214
00215 box_name_ids_[box_names.box_names[ibox]] = ibox;
00216 }
00217 else {
00218 box_name_ids_[box_names.box_names[ibox]] = box_ids.box_ids[ibox];
00219 }
00220 }
00221 }
00222
00223 bool FlightController::isStatusActive(const std::string &status_name) {
00224 if(box_name_ids_.count(status_name) == 0) {
00225
00226
00227 throw std::runtime_error(
00228 "Box ID of " + status_name +
00229 " is unknown! You need to call 'initBoxes()' first.");
00230 }
00231
00232 msp::msg::Status status(fw_variant_);
00233 client_.sendMessage(status);
00234
00235
00236 return status.box_mode_flags.count(box_name_ids_.at(status_name));
00237 }
00238
00239 bool FlightController::setRc(const uint16_t roll, const uint16_t pitch,
00240 const uint16_t yaw, const uint16_t throttle,
00241 const uint16_t aux1, const uint16_t aux2,
00242 const uint16_t aux3, const uint16_t aux4,
00243 const std::vector<uint16_t> auxs) {
00244 msp::msg::SetRawRc rc(fw_variant_);
00245
00246 rc.channels.resize(msp::msg::MAX_MAPPABLE_RX_INPUTS);
00247 rc.channels[channel_map_[0]] = roll;
00248 rc.channels[channel_map_[1]] = pitch;
00249 rc.channels[channel_map_[2]] = yaw;
00250 rc.channels[channel_map_[3]] = throttle;
00251
00252 rc.channels.emplace_back(aux1);
00253 rc.channels.emplace_back(aux2);
00254 rc.channels.emplace_back(aux3);
00255 rc.channels.emplace_back(aux4);
00256
00257
00258 rc.channels.insert(std::end(rc.channels), std::begin(auxs), std::end(auxs));
00259
00260
00261 return client_.sendMessageNoWait(rc);
00262 }
00263
00264 bool FlightController::setRc(const std::vector<uint16_t> channels) {
00265 msp::msg::SetRawRc rc(fw_variant_);
00266 rc.channels = channels;
00267 return client_.sendMessageNoWait(rc);
00268 }
00269
00270 bool FlightController::setMotors(
00271 const std::array<uint16_t, msp::msg::N_MOTOR> &motor_values) {
00272 msp::msg::SetMotor motor(fw_variant_);
00273 motor.motor = motor_values;
00274 return client_.sendMessage(motor);
00275 }
00276
00277 int FlightController::updateFeatures(const std::set<std::string> &add,
00278 const std::set<std::string> &remove) {
00279
00280 msp::msg::Feature feature_in(fw_variant_);
00281 if(!client_.sendMessage(feature_in)) return -1;
00282
00283
00284 msp::msg::SetFeature feature_out(fw_variant_);
00285 feature_out.features = feature_in.features;
00286
00287 for(const std::string &a : add) {
00288 feature_out.features.insert(a);
00289 }
00290
00291 for(const std::string &rem : remove) {
00292 feature_out.features.erase(rem);
00293 }
00294
00295
00296 if(feature_out.features == feature_in.features) return 0;
00297
00298 if(!client_.sendMessage(feature_out)) return -1;
00299
00300
00301 if(!saveSettings()) return -1;
00302 if(!reboot()) return -1;
00303
00304 return 1;
00305 }
00306
00307 }