Commit 6f445903 authored by lm's avatar lm

Merge branch 'experimental' of github.com:pixhawk/qgroundcontrol into experimental

parents 80404c9c a6ca7c45
...@@ -39,14 +39,14 @@ quint64 groundTimeUsecs() ...@@ -39,14 +39,14 @@ quint64 groundTimeUsecs()
float limitAngleToPMPIf(float angle) float limitAngleToPMPIf(float angle)
{ {
while (angle > (M_PI+FLT_EPSILON)) while (angle > ((float)M_PI+FLT_EPSILON))
{ {
angle -= 2 * M_PI; angle -= 2.0f * (float)M_PI;
} }
while (angle <= -(M_PI+FLT_EPSILON)) while (angle <= -((float)M_PI+FLT_EPSILON))
{ {
angle += 2 * M_PI; angle += 2.0f * (float)M_PI;
} }
return angle; return angle;
......
...@@ -169,7 +169,7 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -169,7 +169,7 @@ void MAVLinkSimulationMAV::mainloop()
hud.groundspeed = 9; hud.groundspeed = 9;
hud.alt = 123; hud.alt = 123;
hud.heading = 90; hud.heading = 90;
hud.climb = 0.1; hud.climb = 0.1f;
hud.throttle = 90; hud.throttle = 90;
mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud); mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
......
...@@ -49,30 +49,30 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -49,30 +49,30 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay(NULL, "HSI", parent), HDDisplay(NULL, "HSI", parent),
gpsSatellites(), gpsSatellites(),
satellitesUsed(0), satellitesUsed(0),
attXSet(0), attXSet(0.0f),
attYSet(0), attYSet(0.0f),
attYawSet(0), attYawSet(0.0f),
altitudeSet(1.0), altitudeSet(1.0f),
posXSet(0), posXSet(0.0f),
posYSet(0), posYSet(0.0f),
posZSet(0), posZSet(0.0f),
attXSaturation(0.5f), attXSaturation(0.5f),
attYSaturation(0.5f), attYSaturation(0.5f),
attYawSaturation(0.5f), attYawSaturation(0.5f),
posXSaturation(0.05), posXSaturation(0.05f),
posYSaturation(0.05), posYSaturation(0.05f),
altitudeSaturation(1.0), altitudeSaturation(1.0f),
lat(0), lat(0.0f),
lon(0), lon(0.0f),
alt(0), alt(0.0f),
globalAvailable(0), globalAvailable(0),
x(0), x(0.0f),
y(0), y(0.0f),
z(0), z(0.0f),
vx(0), vx(0.0f),
vy(0), vy(0.0f),
vz(0), vz(0.0f),
speed(0), speed(0.0f),
localAvailable(0), localAvailable(0),
roll(0.0f), roll(0.0f),
pitch(0.0f), pitch(0.0f),
...@@ -85,7 +85,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -85,7 +85,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
uiYSetCoordinate(0.0f), uiYSetCoordinate(0.0f),
uiZSetCoordinate(0.0f), uiZSetCoordinate(0.0f),
uiYawSet(0.0f), uiYawSet(0.0f),
metricWidth(4.0f), metricWidth(4.0),
positionLock(false), positionLock(false),
attControlEnabled(false), attControlEnabled(false),
xyControlEnabled(false), xyControlEnabled(false),
...@@ -105,8 +105,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -105,8 +105,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
columns = 1; columns = 1;
this->setAutoFillBackground(true); this->setAutoFillBackground(true);
vwidth = 80; vwidth = 80.0f;
vheight = 80; vheight = 80.0f;
xCenterPos = vwidth/2.0f; xCenterPos = vwidth/2.0f;
yCenterPos = vheight/2.0f + topMargin - bottomMargin; yCenterPos = vheight/2.0f + topMargin - bottomMargin;
...@@ -797,7 +797,7 @@ void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color ...@@ -797,7 +797,7 @@ void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color
// Scale from metric to screen reference coordinates // Scale from metric to screen reference coordinates
QPointF p = metricBodyToRef(in); QPointF p = metricBodyToRef(in);
drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter); drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
radius *= 0.8; radius *= 0.8f;
drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * radius, refLineWidthToPen(0.4f), color, &painter); drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * radius, refLineWidthToPen(0.4f), color, &painter);
painter.setBrush(color); painter.setBrush(color);
drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter); drawCircle(p.x(), p.y(), radius * 0.1f, 0.1f, color, &painter);
...@@ -984,7 +984,7 @@ void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, con ...@@ -984,7 +984,7 @@ void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, con
const float minWidth = maxWidth * 0.3f; const float minWidth = maxWidth * 0.3f;
float angle = atan2(posXSet, -posYSet); float angle = atan2(posXSet, -posYSet);
angle -= M_PI/2.0f; angle -= (float)M_PI/2.0f;
QPolygonF p(6); QPolygonF p(6);
...@@ -1022,7 +1022,7 @@ void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, con ...@@ -1022,7 +1022,7 @@ void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, con
const float minWidth = maxWidth * 0.3f; const float minWidth = maxWidth * 0.3f;
float angle = atan2(attXSet, attYSet); float angle = atan2(attXSet, attYSet);
angle -= M_PI/2.0f; angle -= (float)M_PI/2.0f;
radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation); radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation);
......
...@@ -183,18 +183,6 @@ void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp) ...@@ -183,18 +183,6 @@ void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{ {
javaScript(QString("updateWaypoint(%1,%2,%3,%4,%5,%6);").arg(uas).arg(wpindex).arg(wp->getY()).arg(wp->getX()).arg(wp->getZ()).arg(wp->getAction())); javaScript(QString("updateWaypoint(%1,%2,%3,%4,%5,%6);").arg(uas).arg(wpindex).arg(wp->getY()).arg(wp->getX()).arg(wp->getZ()).arg(wp->getAction()));
} }
}
else
{
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
// if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
// {
// updateWaypointList(uas);
// }
} }
} }
...@@ -355,7 +343,7 @@ void QGCGoogleEarthView::initializeGoogleEarth() ...@@ -355,7 +343,7 @@ void QGCGoogleEarthView::initializeGoogleEarth()
#endif #endif
#ifdef _MSC_VER #ifdef _MSC_VER
QAxObject* doc = webViewWin->querySubObject("Document()"); QAxObject* doc = webViewWin->querySubObject("Document()");
IDispatch* Disp; //IDispatch* Disp;
IDispatch* winDoc = NULL; IDispatch* winDoc = NULL;
//332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2 //332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2
......
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