From 51069e0618f86031ca6f90cbbc811fc9d35256d4 Mon Sep 17 00:00:00 2001 From: LM Date: Fri, 10 Jun 2011 23:18:05 +0200 Subject: [PATCH] Minor compile fixes for v1.0 --- qgroundcontrol.pri | 4 ++-- src/comm/MAVLinkSimulationLink.cc | 8 ++++---- src/ui/map3D/Pixhawk3DWidget.cc | 18 +++++++++--------- src/ui/map3D/WaypointGroupNode.cc | 4 ++-- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri index f79a29984d..407bc98589 100644 --- a/qgroundcontrol.pri +++ b/qgroundcontrol.pri @@ -221,7 +221,7 @@ message("Compiling for linux 32") DEFINES += QGC_LIBFREENECT_ENABLED } - QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR + QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf @@ -295,7 +295,7 @@ linux-g++-64 { DEFINES += QGC_LIBFREENECT_ENABLED } - QMAKE_POST_LINK += && cp -rf $$BASEDIR/models $$DESTDIR + QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 3f716b0d8f..c0cc9a3a1b 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -757,7 +757,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) for (i = onboardParams.begin(); i != onboardParams.end(); ++i) { if (j != 5) { // Pack message and get size of encoded byte string - mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), 0, onboardParams.size(), j); + mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), MAVLINK_TYPE_FLOAT, onboardParams.size(), j); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); //add data into datastream @@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) onboardParams.insert(key, set.param_value); // Pack message and get size of encoded byte string - mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); + mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key)); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); //add data into datastream @@ -806,7 +806,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) float paramValue = onboardParams.value(key); // Pack message and get size of encoded byte string - mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); + mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key)); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); //add data into datastream @@ -818,7 +818,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) float paramValue = onboardParams.value(key); // Pack message and get size of encoded byte string - mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, 0, onboardParams.size(), onboardParams.keys().indexOf(key)); + mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, MAVLINK_TYPE_FLOAT, onboardParams.size(), onboardParams.keys().indexOf(key)); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); //add data into datastream diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index d441d87a99..009e962cb5 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text) if (text.compare("Global") == 0) { frame = MAV_FRAME_GLOBAL; } else if (text.compare("Local") == 0) { - frame = MAV_FRAME_LOCAL; + frame = MAV_FRAME_LOCAL_NED; } getPosition(lastRobotX, lastRobotY, lastRobotZ); @@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void) getGlobalCursorPosition(getMouseX(), getMouseY(), altitude); target.set(cursorWorldCoords.first, cursorWorldCoords.second); - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { double z = uas->getLocalZ(); std::pair cursorWorldCoords = @@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void) latitude, longitude); wp = new Waypoint(0, longitude, latitude, altitude); - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { double z = uas->getLocalZ(); std::pair cursorWorldCoords = @@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void) waypoint->setX(longitude); waypoint->setY(latitude); waypoint->setZ(altitude); - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { double z = uas->getLocalZ(); std::pair cursorWorldCoords = @@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) Waypoint* waypoint = waypoints.at(selectedWpIndex); double altitude = waypoint->getZ(); - if (frame == MAV_FRAME_LOCAL) { + if (frame == MAV_FRAME_LOCAL_NED) { altitude = -altitude; } @@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) if (ok) { if (frame == MAV_FRAME_GLOBAL) { waypoint->setZ(newAltitude); - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { waypoint->setZ(-newAltitude); } } @@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z, Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); z = -altitude; - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { x = uas->getLocalX(); y = uas->getLocalY(); z = uas->getLocalZ(); @@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z, Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); z = -altitude; - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { x = uas->getLocalX(); y = uas->getLocalY(); z = uas->getLocalZ(); @@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ, oss.precision(6); oss << " Cursor [" << cursorLatitude << " " << cursorLongitude << "]"; - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { oss << " x = " << robotX << " y = " << robotY << " z = " << robotZ << diff --git a/src/ui/map3D/WaypointGroupNode.cc b/src/ui/map3D/WaypointGroupNode.cc index 5dc99cc585..ffacfc42f0 100644 --- a/src/ui/map3D/WaypointGroupNode.cc +++ b/src/ui/map3D/WaypointGroupNode.cc @@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas) QString utmZone; Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone); robotZ = -altitude; - } else if (frame == MAV_FRAME_LOCAL) { + } else if (frame == MAV_FRAME_LOCAL_NED) { robotX = uas->getLocalX(); robotY = uas->getLocalY(); robotZ = uas->getLocalZ(); @@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z) QString utmZone; Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); z = -altitude; - } else if (wp->getFrame() == MAV_FRAME_LOCAL) { + } else if (wp->getFrame() == MAV_FRAME_LOCAL_NED) { x = wp->getX(); y = wp->getY(); z = wp->getZ(); -- GitLab