client_read_test.cpp
Go to the documentation of this file.
00001 #include <Client.hpp>
00002 #include <iostream>
00003 #include <msp_msg.hpp>
00004 
00005 int main(int argc, char *argv[]) {
00006     const std::string device =
00007         (argc > 1) ? std::string(argv[1]) : "/dev/ttyUSB0";
00008     const size_t baudrate = (argc > 2) ? std::stoul(argv[2]) : 115200;
00009 
00010     msp::client::Client client;
00011     client.setLoggingLevel(msp::client::LoggingLevel::WARNING);
00012     client.setVariant(msp::FirmwareVariant::INAV);
00013     client.start(device, baudrate);
00014 
00015     msp::FirmwareVariant fw_variant = msp::FirmwareVariant::INAV;
00016 
00017     msp::msg::Ident ident(fw_variant);
00018     if(client.sendMessage(ident) == 1) {
00019         std::cout << ident;
00020     }
00021     else
00022         std::cerr << "unsupported: " << size_t(ident.id()) << std::endl;
00023 
00024     msp::msg::Status status(fw_variant);
00025     if(client.sendMessage(status) == 1)
00026         std::cout << status;
00027     else
00028         std::cerr << "unsupported: " << size_t(status.id()) << std::endl;
00029 
00030     msp::msg::RawImu imu_raw(fw_variant);
00031     if(client.sendMessage(imu_raw) == 1) {
00032         std::cout << imu_raw;
00033         std::cout << msp::msg::ImuSI(
00034             imu_raw, 512.0, 1.0 / 4.096, 0.92f / 10.0f, 9.80665f);
00035     }
00036     else
00037         std::cerr << "unsupported: " << size_t(imu_raw.id()) << std::endl;
00038 
00039     msp::msg::Servo servo(fw_variant);
00040     if(client.sendMessage(servo) == 1)
00041         std::cout << servo;
00042     else
00043         std::cerr << "unsupported: " << size_t(servo.id()) << std::endl;
00044 
00045     msp::msg::Motor motor(fw_variant);
00046     if(client.sendMessage(motor) == 1)
00047         std::cout << motor;
00048     else
00049         std::cerr << "unsupported: " << size_t(motor.id()) << std::endl;
00050 
00051     msp::msg::Rc rc(fw_variant);
00052     if(client.sendMessage(rc) == 1)
00053         std::cout << rc;
00054     else
00055         std::cerr << "unsupported: " << size_t(rc.id()) << std::endl;
00056 
00057     msp::msg::Attitude attitude(fw_variant);
00058     if(client.sendMessage(attitude) == 1)
00059         std::cout << attitude;
00060     else
00061         std::cerr << "unsupported: " << size_t(attitude.id()) << std::endl;
00062 
00063     msp::msg::Altitude altitude(fw_variant);
00064     if(client.sendMessage(altitude) == 1)
00065         std::cout << altitude;
00066     else
00067         std::cerr << "unsupported: " << size_t(altitude.id()) << std::endl;
00068 
00069     msp::msg::Analog analog(fw_variant);
00070     if(client.sendMessage(analog) == 1)
00071         std::cout << analog;
00072     else
00073         std::cerr << "unsupported: " << size_t(analog.id()) << std::endl;
00074 
00075     msp::msg::RcTuning rc_tuning(fw_variant);
00076     if(client.sendMessage(rc_tuning) == 1)
00077         std::cout << rc_tuning;
00078     else
00079         std::cerr << "unsupported: " << size_t(rc_tuning.id()) << std::endl;
00080 
00081     msp::msg::Pid pid(fw_variant);
00082     if(client.sendMessage(pid) == 1)
00083         std::cout << pid;
00084     else
00085         std::cerr << "unsupported: " << size_t(pid.id()) << std::endl;
00086 
00087     msp::msg::ActiveBoxes box(fw_variant);
00088     if(client.sendMessage(box) == 1)
00089         std::cout << box;
00090     else
00091         std::cerr << "unsupported: " << size_t(box.id()) << std::endl;
00092 
00093     msp::msg::Misc misc(fw_variant);
00094     if(client.sendMessage(misc) == 1)
00095         std::cout << misc;
00096     else
00097         std::cerr << "unsupported: " << size_t(misc.id()) << std::endl;
00098 
00099     msp::msg::MotorPins pins(fw_variant);
00100     if(client.sendMessage(pins) == 1)
00101         std::cout << pins;
00102     else
00103         std::cerr << "unsupported: " << size_t(pins.id()) << std::endl;
00104 
00105     msp::msg::BoxNames box_names(fw_variant);
00106     if(client.sendMessage(box_names) == 1)
00107         std::cout << box_names;
00108     else
00109         std::cerr << "unsupported: " << size_t(box_names.id()) << std::endl;
00110 
00111     msp::msg::PidNames pid_names(fw_variant);
00112     if(client.sendMessage(pid_names) == 1)
00113         std::cout << pid_names;
00114     else
00115         std::cerr << "unsupported: " << size_t(pid_names.id()) << std::endl;
00116 
00117     msp::msg::BoxIds box_ids(fw_variant);
00118     if(client.sendMessage(box_ids) == 1)
00119         std::cout << box_ids;
00120     else
00121         std::cerr << "unsupported: " << size_t(box_ids.id()) << std::endl;
00122 
00123     msp::msg::ServoConf servo_conf(fw_variant);
00124     if(client.sendMessage(servo_conf) == 1)
00125         std::cout << servo_conf;
00126     else
00127         std::cerr << "unsupported: " << size_t(servo_conf.id()) << std::endl;
00128 
00129     // needs "#define DEBUGMSG" in MultiWii firmware
00130 
00131     msp::msg::DebugMessage debug_msg(fw_variant);
00132     if(client.sendMessage(debug_msg) == 1) {
00133         std::cout << "#Debug message:" << std::endl;
00134         std::cout << debug_msg.debug_msg << std::endl;
00135     }
00136     else
00137         std::cerr << "unsupported: " << size_t(debug_msg.id()) << std::endl;
00138 
00139     msp::msg::Debug debug(fw_variant);
00140     if(client.sendMessage(debug) == 1)
00141         std::cout << debug;
00142     else
00143         std::cerr << "unsupported: " << size_t(debug.id()) << std::endl;
00144 
00145     client.stop();
00146     std::cout << "PROGRAM COMPLETE" << std::endl;
00147 }


msp
Author(s): Christian Rauch
autogenerated on Thu Jun 20 2019 19:40:38