diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 82bfc7900e5b30e1cc91333d14b027b0b441f1cc..1b1d1afb0151f72620b468cfc5d70344bedf1d93 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -322,7 +322,8 @@ HEADERS += src/MG.h \ src/libs/qextserialport/qextserialenumerator.h \ src/QGCGeo.h \ src/ui/QGCToolBar.h \ - src/ui/QGCMAVLinkInspector.h + src/ui/QGCMAVLinkInspector.h \ + src/ui/MAVLinkDecoder.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -447,7 +448,8 @@ SOURCES += src/main.cc \ src/ui/map/QGCMapTool.cc \ src/ui/map/QGCMapToolBar.cc \ src/ui/QGCToolBar.cc \ - src/ui/QGCMAVLinkInspector.cc + src/ui/QGCMAVLinkInspector.cc \ + src/ui/MAVLinkDecoder.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 3f716b0d8ffa4a9b86a12bddfa403eca1159c42a..01015fe6107cbd9869009def526434dea28f3717 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -431,6 +431,7 @@ void MAVLinkSimulationLink::mainloop() static int rcCounter = 0; if (rcCounter == 2) { mavlink_rc_channels_raw_t chan; + chan.time_boot_ms = 0; chan.chan1_raw = 1000 + ((int)(fabs(x) * 1000) % 2000); chan.chan2_raw = 1000 + ((int)(fabs(y) * 1000) % 2000); chan.chan3_raw = 1000 + ((int)(fabs(z) * 1000) % 2000); diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 185d9ac01c113c294e3d6bb14f02fe5abba138f8..5d3ee1848992b376536a20197771ca4af18cd8d2 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -73,6 +73,7 @@ void MAVLinkSimulationMAV::mainloop() planner.handleMessage(msg); mavlink_servo_output_raw_t servos; + servos.time_usec = 0; servos.servo1_raw = 1000; servos.servo2_raw = 1250; servos.servo3_raw = 1400; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index c42033596ffeeab813a366a3ebd8cf41844f6d0d..269fcd63c38e13c917d8ddee1deb126cc9dea968 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -314,7 +314,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_sys_status_decode(&message, &state); emit loadChanged(this,state.load/10.0f); - emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime()); + // FIXME REMOVE LATER emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime()); currentVoltage = state.voltage_battery/1000.0f; lpVoltage = filterVoltage(currentVoltage); @@ -349,15 +349,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_raw_imu_decode(&message, &raw); quint64 time = getUnixTime(raw.time_usec); - emit valueChanged(uasId, "accel x", "raw", static_cast(raw.xacc), time); - emit valueChanged(uasId, "accel y", "raw", static_cast(raw.yacc), time); - emit valueChanged(uasId, "accel z", "raw", static_cast(raw.zacc), time); - emit valueChanged(uasId, "gyro roll", "raw", static_cast(raw.xgyro), time); - emit valueChanged(uasId, "gyro pitch", "raw", static_cast(raw.ygyro), time); - emit valueChanged(uasId, "gyro yaw", "raw", static_cast(raw.zgyro), time); - emit valueChanged(uasId, "mag x", "raw", static_cast(raw.xmag), time); - emit valueChanged(uasId, "mag y", "raw", static_cast(raw.ymag), time); - emit valueChanged(uasId, "mag z", "raw", static_cast(raw.zmag), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel x", "raw", static_cast(raw.xacc), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel y", "raw", static_cast(raw.yacc), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel z", "raw", static_cast(raw.zacc), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro roll", "raw", static_cast(raw.xgyro), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro pitch", "raw", static_cast(raw.ygyro), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro yaw", "raw", static_cast(raw.zgyro), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag x", "raw", static_cast(raw.xmag), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag y", "raw", static_cast(raw.ymag), time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag z", "raw", static_cast(raw.zmag), time); } break; case MAVLINK_MSG_ID_SCALED_IMU: @@ -366,15 +366,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_scaled_imu_decode(&message, &scaled); quint64 time = getUnixTime(scaled.time_boot_ms); - emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time); - emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time); - emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time); - emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time); - emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time); - emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time); - emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time); - emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time); - emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time); } break; case MAVLINK_MSG_ID_ATTITUDE: @@ -386,12 +386,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) roll = QGC::limitAngleToPMPIf(attitude.roll); pitch = QGC::limitAngleToPMPIf(attitude.pitch); yaw = QGC::limitAngleToPMPIf(attitude.yaw); - emit valueChanged(uasId, "roll", "rad", roll, time); - emit valueChanged(uasId, "pitch", "rad", pitch, time); - emit valueChanged(uasId, "yaw", "rad", yaw, time); - emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time); - emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time); - emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "roll", "rad", roll, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "pitch", "rad", pitch, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "yaw", "rad", yaw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time); // Emit in angles @@ -404,12 +404,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) attitudeKnown = true; - emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time); - emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time); - emit valueChanged(uasId, "heading deg", "deg", compass, time); - emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time); - emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time); - emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "heading deg", "deg", compass, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time); emit attitudeChanged(this, roll, pitch, yaw, time); emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); @@ -428,12 +428,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_vfr_hud_decode(&message, &hud); quint64 time = getUnixTime(); // Display updated values - emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time); - emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time); - emit valueChanged(uasId, "altitude", "m", hud.alt, time); - emit valueChanged(uasId, "heading", "deg", hud.heading, time); - emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time); - emit valueChanged(uasId, "throttle", "%", hud.throttle, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", hud.alt, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "heading", "deg", hud.heading, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "throttle", "%", hud.throttle, time); emit thrustChanged(this, hud.throttle/100.0); if (!attitudeKnown) @@ -453,14 +453,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_nav_controller_output_decode(&message, &nav); quint64 time = getUnixTime(); // Update UI - emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time); - emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time); - emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time); - emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time); - emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time); - emit valueChanged(uasId, "alt err", "m", nav.alt_error, time); - emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time); - emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "alt err", "m", nav.alt_error, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time); } break; case MAVLINK_MSG_ID_LOCAL_POSITION: @@ -473,12 +473,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) localX = pos.x; localY = pos.y; localZ = pos.z; - emit valueChanged(uasId, "x", "m", pos.x, time); - emit valueChanged(uasId, "y", "m", pos.y, time); - emit valueChanged(uasId, "z", "m", pos.z, time); - emit valueChanged(uasId, "x speed", "m/s", pos.vx, time); - emit valueChanged(uasId, "y speed", "m/s", pos.vy, time); - emit valueChanged(uasId, "z speed", "m/s", pos.vz, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "x", "m", pos.x, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "y", "m", pos.y, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "z", "m", pos.z, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "x speed", "m/s", pos.vx, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "y speed", "m/s", pos.vy, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "z speed", "m/s", pos.vz, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); @@ -507,11 +507,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) speedX = pos.vx/100.0; speedY = pos.vy/100.0; speedZ = pos.vz/100.0; - emit valueChanged(uasId, "latitude", "deg", latitude, time); - emit valueChanged(uasId, "longitude", "deg", longitude, time); - emit valueChanged(uasId, "altitude", "m", altitude, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "latitude", "deg", latitude, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "longitude", "deg", longitude, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", altitude, time); double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ); - emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time); emit globalPositionChanged(this, latitude, longitude, altitude, time); emit speedChanged(this, speedX, speedY, speedZ, time); // Set internal state @@ -534,13 +534,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // quint64 time = getUnixTime(pos.time_usec); quint64 time = getUnixTime(pos.time_usec); - emit valueChanged(uasId, "gps latitude", "deg", pos.lat/(double)1E7, time); - emit valueChanged(uasId, "gps longitude", "deg", pos.lon/(double)1E7, time); - emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time); - emit valueChanged(uasId, "gps eph", "m", pos.eph/(double)1E2, time); - emit valueChanged(uasId, "gps epv", "m", pos.eph/(double)1E2, time); - emit valueChanged(uasId, "gps fix", "raw", pos.fix_type, time); - emit valueChanged(uasId, "gps course", "raw", pos.cog, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps latitude", "deg", pos.lat/(double)1E7, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps longitude", "deg", pos.lon/(double)1E7, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps eph", "m", pos.eph/(double)1E2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps epv", "m", pos.eph/(double)1E2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps fix", "raw", pos.fix_type, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "gps course", "raw", pos.cog, time); if (pos.fix_type > 2) { emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time); @@ -555,13 +555,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) alt = 0; emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); } - emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", pos.alt/(double)1E3, time); // Smaller than threshold and not NaN float vel = pos.vel/100.0f; if (vel < 1000000 && !isnan(vel) && !isinf(vel)) { - emit valueChanged(uasId, "speed", "m/s", vel, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "speed", "m/s", vel, time); //qDebug() << "GOT GPS RAW"; // emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); } else { @@ -592,10 +592,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_raw_pressure_t pressure; mavlink_msg_raw_pressure_decode(&message, &pressure); quint64 time = this->getUnixTime(pressure.time_usec); - emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time); - emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time); - emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time); - emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time); } break; @@ -604,9 +604,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_scaled_pressure_t pressure; mavlink_msg_scaled_pressure_decode(&message, &pressure); quint64 time = this->getUnixTime(pressure.time_boot_ms); - emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); - emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time); - emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time); } break; @@ -624,14 +624,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit remoteControlChannelRawChanged(6, channels.chan7_raw); emit remoteControlChannelRawChanged(7, channels.chan8_raw); quint64 time = getUnixTime(); - emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time); - emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time); - emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time); - emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time); - emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time); - emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time); - emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time); - emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time); } break; case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: @@ -715,7 +715,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } break; case MAVLINK_MSG_ID_DEBUG: - emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow()); + // FIXME REMOVE LATER emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow()); break; case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT: { @@ -723,10 +723,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out); quint64 time = getUnixTimeFromMs(out.time_boot_ms); emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time); - emit valueChanged(uasId, "att control roll", "rad", out.roll, time); - emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time); - emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time); - emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "att control roll", "rad", out.roll, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time); } break; case MAVLINK_MSG_ID_WAYPOINT_COUNT: @@ -817,14 +817,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_servo_output_raw_t servos; mavlink_msg_servo_output_raw_decode(&message, &servos); quint64 time = getUnixTime(); - emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time); - emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time); - emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time); - emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time); - emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time); - emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time); - emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time); - emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time); } break; @@ -832,12 +832,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) { mavlink_optical_flow_t flow; mavlink_msg_optical_flow_decode(&message, &flow); - quint64 time = getUnixTime(flow.time); + quint64 time = getUnixTime(flow.time_usec); - emit valueChanged(uasId, QString("opt_flow_%1.x").arg(flow.sensor_id), "Pixel", flow.flow_x, time); - emit valueChanged(uasId, QString("opt_flow_%1.y").arg(flow.sensor_id), "Pixel", flow.flow_y, time); - emit valueChanged(uasId, QString("opt_flow_%1.qual").arg(flow.sensor_id), "0-255", flow.quality, time); - emit valueChanged(uasId, QString("opt_flow_%1.dist").arg(flow.sensor_id), "m", flow.ground_distance, time); + // FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.x").arg(flow.sensor_id), "Pixel", flow.flow_x, time); + // FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.y").arg(flow.sensor_id), "Pixel", flow.flow_y, time); + // FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.qual").arg(flow.sensor_id), "0-255", flow.quality, time); + // FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.dist").arg(flow.sensor_id), "m", flow.ground_distance, time); } break; case MAVLINK_MSG_ID_STATUSTEXT: @@ -910,19 +910,19 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_msg_debug_vect_decode(&message, &vect); QString str((const char*)vect.name); quint64 time = getUnixTime(vect.time_usec); - emit valueChanged(uasId, str+".x", "raw", vect.x, time); - emit valueChanged(uasId, str+".y", "raw", vect.y, time); - emit valueChanged(uasId, str+".z", "raw", vect.z, time); - } - break; - case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT: - { - mavlink_object_detection_event_t event; - mavlink_msg_object_detection_event_decode(&message, &event); - QString str(event.name); - emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance); + // FIXME REMOVE LATER emit valueChanged(uasId, str+".x", "raw", vect.x, time); + // FIXME REMOVE LATER emit valueChanged(uasId, str+".y", "raw", vect.y, time); + // FIXME REMOVE LATER emit valueChanged(uasId, str+".z", "raw", vect.z, time); } break; +// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT: +// { +// mavlink_object_detection_event_t event; +// mavlink_msg_object_detection_event_decode(&message, &event); +// QString str(event.name); +// emit objectDetected(event.time, event.object_id, event.type, str, event.quality, event.bearing, event.distance); +// } +// break; // WILL BE ENABLED ONCE MESSAGE IS IN COMMON MESSAGE SET // case MAVLINK_MSG_ID_MEMORY_VECT: // { @@ -942,31 +942,31 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // default: // case 0: // for (int i = 0; i < 16; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "i16", mem0[i], time); // break; // case 1: // for (int i = 0; i < 16; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "ui16", mem1[i], time); // break; // case 2: // for (int i = 0; i < 16; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "Q15", (float)mem0[i]/32767.0, time); // break; // case 3: // for (int i = 0; i < 16; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*2)), "1Q14", (float)mem0[i]/16383.0, time); // break; // case 4: // for (int i = 0; i < 8; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); // break; // case 5: // for (int i = 0; i < 8; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "i32", mem2[i], time); // break; // case 6: // for (int i = 0; i < 8; i++) -// emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time); +// // FIXME REMOVE LATER emit valueChanged(uasId, str.arg(vect.address+(i*4)), "float", mem4[i], time); // break; // } // } @@ -978,12 +978,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_nav_filter_bias_t bias; mavlink_msg_nav_filter_bias_decode(&message, &bias); quint64 time = getUnixTime(); - emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time); - emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time); - emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time); - emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time); - emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time); - emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[0]", "raw", bias.accel_0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[1]", "raw", bias.accel_1, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_f[2]", "raw", bias.accel_2, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[0]", "raw", bias.gyro_0, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[1]", "raw", bias.gyro_1, time); + // FIXME REMOVE LATER emit valueChanged(uasId, "b_w[2]", "raw", bias.gyro_2, time); } break; case MAVLINK_MSG_ID_RADIO_CALIBRATION: diff --git a/src/ui/MAVLinkDecoder.cc b/src/ui/MAVLinkDecoder.cc new file mode 100644 index 0000000000000000000000000000000000000000..85e582fee0d5a2f679ca4bacd00867cd5f43c14d --- /dev/null +++ b/src/ui/MAVLinkDecoder.cc @@ -0,0 +1,260 @@ +#include "MAVLinkDecoder.h" +#include "UASManager.h" + +MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : + QObject(parent) +{ + mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO; + memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256); + memset(receivedMessages, 0, sizeof(mavlink_message_t)*256); + + connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t))); +} + +void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t message) +{ + Q_UNUSED(link); + memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t)); + + uint8_t msgid = message.msgid; + QString messageName("%1 (#%2)"); + messageName = messageName.arg(messageInfo[msgid].name).arg(msgid); + + // See if first value is a time value + quint64 time = 0; + uint8_t fieldid = 0; + uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8; + if (messageInfo[msgid].fields[fieldid].name == "time_boot_ms" && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT32_T) + { + time = *((quint32*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + } + else if (messageInfo[msgid].fields[fieldid].name == "time_usec" && messageInfo[msgid].fields[fieldid].type == MAVLINK_TYPE_UINT64_T) + { + time = *((quint64*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + } + else + { + emitFieldValue(&message, fieldid, time); + } + + // Send out field values + for (unsigned int i = 1; i < messageInfo[msgid].num_fields; ++i) + { + emitFieldValue(&message, i, time); + } + + // Send out combined math expressions + // FIXME XXX TODO +} + +void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time) +{ + // Add field tree widget item + uint8_t msgid = msg->msgid; + QString fieldName(messageInfo[msgid].fields[fieldid].name); + QString fieldType; + uint8_t* m = ((uint8_t*)(receivedMessages+msgid))+8; + QString name("%1.%2"); + QString unit(""); + name = name.arg(messageInfo[msgid].name, fieldName); + switch (messageInfo[msgid].fields[fieldid].type) + { + case MAVLINK_TYPE_CHAR: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + char* str = (char*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + // Enforce null termination + str[messageInfo[msgid].fields[fieldid].array_length-1] = '\0'; + QString string(name + ": " + str); + emit textMessageReceived(msg->sysid, msg->compid, 0, string); + } + else + { + // Single char + char b = *((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + unit = QString("char[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + emit valueChanged(msg->sysid, name, unit, b, time); + } + break; + case MAVLINK_TYPE_UINT8_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + uint8_t* nums = m+messageInfo[msgid].fields[fieldid].wire_offset; + fieldType = QString("uint8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[fieldid].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + uint8_t u = *(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = "uint8_t"; + emit valueChanged(msg->sysid, name, fieldType, u, time); + } + break; + case MAVLINK_TYPE_INT8_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + int8_t* nums = (int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("int8_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + int8_t n = *((int8_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "int8_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_UINT16_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + uint16_t* nums = (uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("uint16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + uint16_t n = *((uint16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "uint16_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_INT16_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + int16_t* nums = (int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("int16_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + int16_t n = *((int16_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "int16_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_UINT32_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + uint32_t* nums = (uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("uint32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + float n = *((uint32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "uint32_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_INT32_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + int32_t* nums = (int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("int32_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + int32_t n = *((int32_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "int32_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_FLOAT: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + float* nums = (float*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("float[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + float f = *((float*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "float"; + emit valueChanged(msg->sysid, name, fieldType, f, time); + } + break; + case MAVLINK_TYPE_DOUBLE: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + double* nums = (double*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("double[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + double f = *((double*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "double"; + emit valueChanged(msg->sysid, name, fieldType, f, time); + } + break; + case MAVLINK_TYPE_UINT64_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + uint64_t* nums = (uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("uint64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + uint64_t n = *((uint64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "uint64_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + case MAVLINK_TYPE_INT64_T: + if (messageInfo[msgid].fields[fieldid].array_length > 0) + { + int64_t* nums = (int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset); + fieldType = QString("int64_t[%1]").arg(messageInfo[msgid].fields[fieldid].array_length); + for (unsigned int j = 0; j < messageInfo[msgid].fields[j].array_length; ++j) + { + emit valueChanged(msg->sysid, QString("%1.%2").arg(name).arg(j), fieldType, nums[j], time); + } + } + else + { + // Single value + int64_t n = *((int64_t*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); + fieldType = "int64_t"; + emit valueChanged(msg->sysid, name, fieldType, n, time); + } + break; + } +} diff --git a/src/ui/MAVLinkDecoder.h b/src/ui/MAVLinkDecoder.h new file mode 100644 index 0000000000000000000000000000000000000000..6f1c271278e291962f0364747718fa1793b721ba --- /dev/null +++ b/src/ui/MAVLinkDecoder.h @@ -0,0 +1,34 @@ +#ifndef MAVLINKDECODER_H +#define MAVLINKDECODER_H + +#include +#include "MAVLinkProtocol.h" + +class MAVLinkDecoder : public QObject +{ + Q_OBJECT +public: + MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent = 0); + +signals: + void textMessageReceived(int uasid, int componentid, int severity, const QString& text); + void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec); + void valueChanged(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec); + void valueChanged(const int uasId, const QString& name, const QString& unit, const unsigned int value, const quint64 msec); + void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec); + void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec); + + +public slots: + /** @brief Receive one message from the protocol and decode it */ + void receiveMessage(LinkInterface* link,mavlink_message_t message); +protected: + /** @brief Emit the value of one message field */ + void emitFieldValue(mavlink_message_t* msg, int fieldid, quint64 time); + + mavlink_message_t receivedMessages[256]; ///< Available / known messages + mavlink_message_info_t messageInfo[256]; + +}; + +#endif // MAVLINKDECODER_H diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index b156ab250b91fec4c591f4a0ec19999ff792d40f..1968e898033de9de1f831f48d0825e1dd82e2967 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -153,6 +153,9 @@ MainWindow::MainWindow(QWidget *parent): connect(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)), this, SLOT(addLink(LinkInterface*))); + // Add generic MAVLink decoder + mavlinkDecoder = new MAVLinkDecoder(mavlink, this); + // Connect user interface devices joystickWidget = 0; joystick = new JoystickInput(); @@ -439,6 +442,7 @@ void MainWindow::buildPxWidgets() if (!linechartWidget) { // Center widgets linechartWidget = new Linecharts(this); + linechartWidget->addSource(mavlinkDecoder); addToCentralWidgetsMenu(linechartWidget, tr("Realtime Plot"), SLOT(showCentralWidget()), CENTRAL_LINECHART); } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 1bacebc985a2f5559c3106e6af7a099923985246..fbc262d1942301f11aaa37e65cf788c4e83ca172 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -77,6 +77,8 @@ This file is part of the QGROUNDCONTROL project #include "UASControlParameters.h" #include "QGCMAVLinkInspector.h" +#include "MAVLinkDecoder.h" + class QGCMapTool; /** @@ -426,6 +428,7 @@ protected: QPointer toolBar; QPointer mavlinkInspectorWidget; + QPointer mavlinkDecoder; // Popup widgets diff --git a/src/ui/linechart/LinechartPlot.cc b/src/ui/linechart/LinechartPlot.cc index 74a2b2dc231c3077e2b8e96e8b464adb21ff257e..8c04d930bb8bf1b136c1cea7437aa9597867ea09 100644 --- a/src/ui/linechart/LinechartPlot.cc +++ b/src/ui/linechart/LinechartPlot.cc @@ -1,4 +1,4 @@ -/*===================================================================== + /*===================================================================== ======================================================================*/ /** diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index ae5981f0b7570ae7ddb553aa9f0e01d3185e4b44..9ea49a887b027cdae144c4db09cef1d149056195 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -71,7 +71,8 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent logindex(1), logging(false), logStartTime(0), - updateTimer(new QTimer()) + updateTimer(new QTimer()), + selectedMAV(-1) { // Add elements defined in Qt Designer ui.setupUi(this); @@ -292,20 +293,24 @@ void LinechartWidget::createLayout() void LinechartWidget::appendData(int uasId, QString curve, double value, quint64 usec) { static const QString unit("-"); - if (isVisible()) { + if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible())) + { // Order matters here, first append to plot, then update curve list activePlot->appendData(curve+unit, usec, value); // Store data QLabel* label = curveLabels->value(curve+unit, NULL); // Make sure the curve will be created if it does not yet exist - if(!label) { + if(!label) + { addCurve(curve, unit); } } // Log data - if (logging) { - if (activePlot->isVisible(curve+unit)) { + if (logging) + { + if (activePlot->isVisible(curve+unit)) + { if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; @@ -319,21 +324,25 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64 void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec) { - if (isVisible()) { + if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible())) + { // Order matters here, first append to plot, then update curve list activePlot->appendData(curve+unit, usec, value); // Store data QLabel* label = curveLabels->value(curve+unit, NULL); // Make sure the curve will be created if it does not yet exist - if(!label) { + if(!label) + { //qDebug() << "ADDING CURVE IN APPENDDATE DOUBLE"; addCurve(curve, unit); } } // Log data - if (logging) { - if (activePlot->isVisible(curve+unit)) { + if (logging) + { + if (activePlot->isVisible(curve+unit)) + { if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; @@ -346,13 +355,25 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, int value, quint64 usec) { - if (isVisible()) { + appendData(uasId, curve, unit, static_cast(value), usec); +} + +void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, unsigned int value, quint64 usec) +{ + appendData(uasId, curve, unit, static_cast(value), usec); +} + +void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint64 value, quint64 usec) +{ + if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible())) + { // Order matters here, first append to plot, then update curve list activePlot->appendData(curve+unit, usec, value); // Store data QLabel* label = curveLabels->value(curve+unit, NULL); // Make sure the curve will be created if it does not yet exist - if(!label) { + if(!label) + { intData.insert(curve+unit, 0); addCurve(curve, unit); } @@ -362,8 +383,44 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& } // Log data - if (logging) { - if (activePlot->isVisible(curve+unit)) { + if (logging) + { + if (activePlot->isVisible(curve+unit)) + { + if (logStartTime == 0) logStartTime = usec; + qint64 time = usec - logStartTime; + if (time < 0) time = 0; + + logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1()); + logFile->flush(); + } + } +} + +void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint64 value, quint64 usec) +{ + if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible())) + { + // Order matters here, first append to plot, then update curve list + activePlot->appendData(curve+unit, usec, value); + // Store data + QLabel* label = curveLabels->value(curve+unit, NULL); + // Make sure the curve will be created if it does not yet exist + if(!label) + { + intData.insert(curve+unit, 0); + addCurve(curve, unit); + } + + // Add int data + intData.insert(curve+unit, value); + } + + // Log data + if (logging) + { + if (activePlot->isVisible(curve+unit)) + { if (logStartTime == 0) logStartTime = usec; qint64 time = usec - logStartTime; if (time < 0) time = 0; diff --git a/src/ui/linechart/LinechartWidget.h b/src/ui/linechart/LinechartWidget.h index 1b58f911b2b50af11055e47409ee568410a46995..4e33d52ed3ec9f67d6f12308ea27c8a06bde27d1 100644 --- a/src/ui/linechart/LinechartWidget.h +++ b/src/ui/linechart/LinechartWidget.h @@ -79,6 +79,12 @@ public slots: void appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec); /** @brief Append data as int with unit */ void appendData(int uasId, const QString& curve, const QString& unit, int value, quint64 usec); + /** @brief Append data as unsigned int with unit */ + void appendData(int uasId, const QString& curve, const QString& unit, unsigned int value, quint64 usec); + /** @brief Append data as int64 with unit */ + void appendData(int uasId, const QString& curve, const QString& unit, qint64 value, quint64 usec); + /** @brief Append data as uint64 with unit */ + void appendData(int uasId, const QString& curve, const QString& unit, quint64 value, quint64 usec); void takeButtonClick(bool checked); void setPlotWindowPosition(int scrollBarValue); void setPlotWindowPosition(quint64 position); @@ -88,6 +94,11 @@ public slots: /** @brief Stop automatic updates once hidden */ void hideEvent(QHideEvent* event); void setActive(bool active); + void setActiveSystem(int systemid) + { + selectedMAV = systemid; + } + /** @brief Set the number of values to average over */ void setAverageWindow(int windowSize); /** @brief Start logging to file */ @@ -149,6 +160,7 @@ protected: QTimer* updateTimer; LogCompressor* compressor; QCheckBox* selectAllCheckBox; + int selectedMAV; ///< The MAV for which plot items are accepted, -1 for all systems static const int updateInterval = 400; ///< Time between number updates, in milliseconds static const int MAX_CURVE_MENUITEM_NUMBER = 8; diff --git a/src/ui/linechart/Linecharts.cc b/src/ui/linechart/Linecharts.cc index af1fded4f8ed916b736cf16e88b4e1906b9fc490..be59afe9910bc347f6f67eef254b1abd1c11438e 100644 --- a/src/ui/linechart/Linecharts.cc +++ b/src/ui/linechart/Linecharts.cc @@ -61,25 +61,32 @@ void Linecharts::hideEvent(QHideEvent* event) void Linecharts::selectSystem(int systemid) { QWidget* prevWidget = currentWidget(); - if (prevWidget) { + if (prevWidget) + { LinechartWidget* chart = dynamic_cast(prevWidget); - if (chart) { + if (chart) + { chart->setActive(false); + chart->setActiveSystem(systemid); } } QWidget* widget = plots.value(systemid, NULL); - if (widget) { + if (widget) + { setCurrentWidget(widget); LinechartWidget* chart = dynamic_cast(widget); - if (chart) { + if (chart) + { chart->setActive(true); + chart->setActiveSystem(systemid); } } } void Linecharts::addSystem(UASInterface* uas) { - if (!plots.contains(uas->getUASID())) { + if (!plots.contains(uas->getUASID())) + { LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this); addWidget(widget); plots.insert(uas->getUASID(), widget); @@ -92,10 +99,38 @@ void Linecharts::addSystem(UASInterface* uas) connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString))); // Set system active if this is the only system - if (active) { - if (plots.size() == 1) { + if (active) + { + if (plots.size() == 1) + { + // FIXME XXX HACK + // Connect generic sources + for (int i = 0; i < genericSources.count(); ++i) + { + connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,int,quint64))); + connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,unsigned int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,unsigned int,quint64))); + connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint64,quint64))); + connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64))); + connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64))); + } + // Select system selectSystem(uas->getUASID()); } } } } + +void Linecharts::addSource(QObject* obj) +{ + genericSources.append(obj); + // FIXME XXX HACK + if (plots.size() > 0) + { + // Connect generic source + connect(obj, SIGNAL(valueChanged(int,QString,QString,int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,int,quint64))); + connect(obj, SIGNAL(valueChanged(int,QString,QString,unsigned int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,unsigned int,quint64))); + connect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint64,quint64))); + connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64))); + connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64))); + } +} diff --git a/src/ui/linechart/Linecharts.h b/src/ui/linechart/Linecharts.h index 4b6ad5cce08417a5d5d99ccdb16d0b1b439f1489..4d5d26b20b334565620672de2af0597acad2dc40 100644 --- a/src/ui/linechart/Linecharts.h +++ b/src/ui/linechart/Linecharts.h @@ -3,6 +3,7 @@ #include #include +#include #include "LinechartWidget.h" #include "UASInterface.h" @@ -22,9 +23,12 @@ public slots: void selectSystem(int systemid); /** @brief Add a new system to the list of plots */ void addSystem(UASInterface* uas); + /** @brief Add a new generic message source (not a system) */ + void addSource(QObject* obj); protected: QMap plots; + QVector genericSources; bool active; /** @brief Start updating widget */ void showEvent(QShowEvent* event);