Commit 51069e06 authored by LM's avatar LM

Minor compile fixes for v1.0

parent 7948025a
...@@ -221,7 +221,7 @@ message("Compiling for linux 32") ...@@ -221,7 +221,7 @@ message("Compiling for linux 32")
DEFINES += QGC_LIBFREENECT_ENABLED 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 += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
...@@ -295,7 +295,7 @@ linux-g++-64 { ...@@ -295,7 +295,7 @@ linux-g++-64 {
DEFINES += QGC_LIBFREENECT_ENABLED 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 += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
......
...@@ -757,7 +757,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -757,7 +757,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) { for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) { if (j != 5) {
// Pack message and get size of encoded byte string // 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 // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value); onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string // 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 // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -806,7 +806,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -806,7 +806,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // 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 // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -818,7 +818,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -818,7 +818,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // 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 // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
......
...@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text) ...@@ -139,7 +139,7 @@ Pixhawk3DWidget::selectFrame(QString text)
if (text.compare("Global") == 0) { if (text.compare("Global") == 0) {
frame = MAV_FRAME_GLOBAL; frame = MAV_FRAME_GLOBAL;
} else if (text.compare("Local") == 0) { } else if (text.compare("Local") == 0) {
frame = MAV_FRAME_LOCAL; frame = MAV_FRAME_LOCAL_NED;
} }
getPosition(lastRobotX, lastRobotY, lastRobotZ); getPosition(lastRobotX, lastRobotY, lastRobotZ);
...@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void) ...@@ -231,7 +231,7 @@ Pixhawk3DWidget::selectTarget(void)
getGlobalCursorPosition(getMouseX(), getMouseY(), altitude); getGlobalCursorPosition(getMouseX(), getMouseY(), altitude);
target.set(cursorWorldCoords.first, cursorWorldCoords.second); target.set(cursorWorldCoords.first, cursorWorldCoords.second);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void) ...@@ -266,7 +266,7 @@ Pixhawk3DWidget::insertWaypoint(void)
latitude, longitude); latitude, longitude);
wp = new Waypoint(0, longitude, latitude, altitude); wp = new Waypoint(0, longitude, latitude, altitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void) ...@@ -314,7 +314,7 @@ Pixhawk3DWidget::setWaypoint(void)
waypoint->setX(longitude); waypoint->setX(longitude);
waypoint->setY(latitude); waypoint->setY(latitude);
waypoint->setZ(altitude); waypoint->setZ(altitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
double z = uas->getLocalZ(); double z = uas->getLocalZ();
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
...@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) ...@@ -345,7 +345,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
Waypoint* waypoint = waypoints.at(selectedWpIndex); Waypoint* waypoint = waypoints.at(selectedWpIndex);
double altitude = waypoint->getZ(); double altitude = waypoint->getZ();
if (frame == MAV_FRAME_LOCAL) { if (frame == MAV_FRAME_LOCAL_NED) {
altitude = -altitude; altitude = -altitude;
} }
...@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void) ...@@ -355,7 +355,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
if (ok) { if (ok) {
if (frame == MAV_FRAME_GLOBAL) { if (frame == MAV_FRAME_GLOBAL) {
waypoint->setZ(newAltitude); waypoint->setZ(newAltitude);
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
waypoint->setZ(-newAltitude); waypoint->setZ(-newAltitude);
} }
} }
...@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z, ...@@ -640,7 +640,7 @@ Pixhawk3DWidget::getPose(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX(); x = uas->getLocalX();
y = uas->getLocalY(); y = uas->getLocalY();
z = uas->getLocalZ(); z = uas->getLocalZ();
...@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z, ...@@ -673,7 +673,7 @@ Pixhawk3DWidget::getPosition(double& x, double& y, double& z,
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
x = uas->getLocalX(); x = uas->getLocalX();
y = uas->getLocalY(); y = uas->getLocalY();
z = uas->getLocalZ(); z = uas->getLocalZ();
...@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ, ...@@ -941,7 +941,7 @@ Pixhawk3DWidget::updateHUD(double robotX, double robotY, double robotZ,
oss.precision(6); oss.precision(6);
oss << " Cursor [" << cursorLatitude << oss << " Cursor [" << cursorLatitude <<
" " << cursorLongitude << "]"; " " << cursorLongitude << "]";
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
oss << " x = " << robotX << oss << " x = " << robotX <<
" y = " << robotY << " y = " << robotY <<
" z = " << robotZ << " z = " << robotZ <<
......
...@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas) ...@@ -63,7 +63,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
QString utmZone; QString utmZone;
Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone); Imagery::LLtoUTM(latitude, longitude, robotX, robotY, utmZone);
robotZ = -altitude; robotZ = -altitude;
} else if (frame == MAV_FRAME_LOCAL) { } else if (frame == MAV_FRAME_LOCAL_NED) {
robotX = uas->getLocalX(); robotX = uas->getLocalX();
robotY = uas->getLocalY(); robotY = uas->getLocalY();
robotZ = uas->getLocalZ(); robotZ = uas->getLocalZ();
...@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z) ...@@ -154,7 +154,7 @@ WaypointGroupNode::getPosition(Waypoint* wp, double &x, double &y, double &z)
QString utmZone; QString utmZone;
Imagery::LLtoUTM(latitude, longitude, x, y, utmZone); Imagery::LLtoUTM(latitude, longitude, x, y, utmZone);
z = -altitude; z = -altitude;
} else if (wp->getFrame() == MAV_FRAME_LOCAL) { } else if (wp->getFrame() == MAV_FRAME_LOCAL_NED) {
x = wp->getX(); x = wp->getX();
y = wp->getY(); y = wp->getY();
z = wp->getZ(); z = wp->getZ();
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment