23 changed files with 6415 additions and 4498 deletions
@ -1,12 +0,0 @@
@@ -1,12 +0,0 @@
|
||||
|
||||
For use of qt 4x and visual studio2010 and add in. |
||||
|
||||
The Visual studio adds automatically certain defines |
||||
|
||||
In the projects properties -> C/C++ ->preprocessor change: |
||||
|
||||
in DEBUG: |
||||
delete QT_NO_DEBUG |
||||
|
||||
Both: |
||||
delete QT_NO_DYNAMIC_CAST |
@ -0,0 +1,427 @@
@@ -0,0 +1,427 @@
|
||||
#include "GLOverlayGeode.h" |
||||
|
||||
GLOverlayGeode::GLOverlayGeode() |
||||
: mDrawable(new GLOverlayDrawable) |
||||
, mMessageTimestamp(0.0) |
||||
{ |
||||
addDrawable(mDrawable); |
||||
} |
||||
|
||||
void |
||||
GLOverlayGeode::setOverlay(px::GLOverlay &overlay) |
||||
{ |
||||
mDrawable->setOverlay(overlay); |
||||
mCoordinateFrameType = overlay.coordinateframetype(); |
||||
|
||||
dirtyBound(); |
||||
} |
||||
|
||||
px::GLOverlay::CoordinateFrameType |
||||
GLOverlayGeode::coordinateFrameType(void) const |
||||
{ |
||||
return mCoordinateFrameType; |
||||
} |
||||
|
||||
void |
||||
GLOverlayGeode::setMessageTimestamp(qreal timestamp) |
||||
{ |
||||
mMessageTimestamp = timestamp; |
||||
} |
||||
|
||||
qreal |
||||
GLOverlayGeode::messageTimestamp(void) const |
||||
{ |
||||
return mMessageTimestamp; |
||||
} |
||||
|
||||
GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable() |
||||
{ |
||||
setUseDisplayList(true); |
||||
} |
||||
|
||||
GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable(const GLOverlayDrawable& drawable, |
||||
const osg::CopyOp& copyop) |
||||
: osg::Drawable(drawable,copyop) |
||||
{ |
||||
setUseDisplayList(true); |
||||
} |
||||
|
||||
void |
||||
GLOverlayGeode::GLOverlayDrawable::setOverlay(px::GLOverlay &overlay) |
||||
{ |
||||
if (!overlay.IsInitialized()) |
||||
{ |
||||
return; |
||||
} |
||||
|
||||
mOverlay = overlay; |
||||
|
||||
mBBox.init(); |
||||
|
||||
const std::string& data = mOverlay.data(); |
||||
|
||||
for (size_t i = 0; i < data.size(); ++i) |
||||
{ |
||||
switch (data.at(i)) { |
||||
case px::GLOverlay::POINTS: |
||||
break; |
||||
case px::GLOverlay::LINES: |
||||
break; |
||||
case px::GLOverlay::LINE_STRIP: |
||||
break; |
||||
case px::GLOverlay::LINE_LOOP: |
||||
break; |
||||
case px::GLOverlay::TRIANGLES: |
||||
break; |
||||
case px::GLOverlay::TRIANGLE_STRIP: |
||||
break; |
||||
case px::GLOverlay::TRIANGLE_FAN: |
||||
break; |
||||
case px::GLOverlay::QUADS: |
||||
break; |
||||
case px::GLOverlay::QUAD_STRIP: |
||||
break; |
||||
case px::GLOverlay::POLYGON: |
||||
break; |
||||
case px::GLOverlay::WIRE_CIRCLE: |
||||
i += sizeof(float) * 4; |
||||
break; |
||||
case px::GLOverlay::SOLID_CIRCLE: |
||||
i += sizeof(float) * 4; |
||||
break; |
||||
case px::GLOverlay::SOLID_CUBE: |
||||
i += sizeof(float) * 5; |
||||
break; |
||||
case px::GLOverlay::WIRE_CUBE: |
||||
i += sizeof(float) * 5; |
||||
break; |
||||
case px::GLOverlay::END: |
||||
break; |
||||
case px::GLOverlay::VERTEX2F: |
||||
i += sizeof(float) * 2; |
||||
break; |
||||
case px::GLOverlay::VERTEX3F: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
|
||||
mBBox.expandBy(x, y, z); |
||||
} |
||||
break; |
||||
case px::GLOverlay::ROTATEF: |
||||
i += sizeof(float) * 4; |
||||
break; |
||||
case px::GLOverlay::TRANSLATEF: |
||||
i += sizeof(float) * 3; |
||||
break; |
||||
case px::GLOverlay::SCALEF: |
||||
i += sizeof(float) * 3; |
||||
break; |
||||
case px::GLOverlay::PUSH_MATRIX: |
||||
break; |
||||
case px::GLOverlay::POP_MATRIX: |
||||
break; |
||||
case px::GLOverlay::COLOR3F: |
||||
i += sizeof(float) * 3; |
||||
break; |
||||
case px::GLOverlay::COLOR4F: |
||||
i += sizeof(float) * 4; |
||||
break; |
||||
case px::GLOverlay::POINTSIZE: |
||||
i += sizeof(float); |
||||
break; |
||||
case px::GLOverlay::LINEWIDTH: |
||||
i += sizeof(float); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
dirtyDisplayList(); |
||||
} |
||||
|
||||
void |
||||
GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const |
||||
{ |
||||
if (!mOverlay.IsInitialized()) |
||||
{ |
||||
return; |
||||
} |
||||
|
||||
glPushMatrix(); |
||||
|
||||
glScalef(-1.0f, 1.0f, 1.0f); |
||||
glRotatef(90.0f, 0.0f, 0.0f, 1.0f); |
||||
|
||||
const std::string& data = mOverlay.data(); |
||||
|
||||
for (size_t i = 0; i < data.size(); ++i) |
||||
{ |
||||
switch (data.at(i)) { |
||||
case px::GLOverlay::POINTS: |
||||
glBegin(GL_POINTS); |
||||
break; |
||||
case px::GLOverlay::LINES: |
||||
glBegin(GL_LINES); |
||||
break; |
||||
case px::GLOverlay::LINE_STRIP: |
||||
glBegin(GL_LINE_STRIP); |
||||
break; |
||||
case px::GLOverlay::LINE_LOOP: |
||||
glBegin(GL_LINE_LOOP); |
||||
break; |
||||
case px::GLOverlay::TRIANGLES: |
||||
glBegin(GL_TRIANGLES); |
||||
break; |
||||
case px::GLOverlay::TRIANGLE_STRIP: |
||||
glBegin(GL_TRIANGLE_STRIP); |
||||
break; |
||||
case px::GLOverlay::TRIANGLE_FAN: |
||||
glBegin(GL_TRIANGLE_FAN); |
||||
break; |
||||
case px::GLOverlay::QUADS: |
||||
glBegin(GL_QUADS); |
||||
break; |
||||
case px::GLOverlay::QUAD_STRIP: |
||||
glBegin(GL_QUAD_STRIP); |
||||
break; |
||||
case px::GLOverlay::POLYGON: |
||||
glBegin(GL_POLYGON); |
||||
break; |
||||
case px::GLOverlay::WIRE_CIRCLE: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
float r = getFloatValue(data, i); |
||||
|
||||
glBegin(GL_LINE_LOOP); |
||||
for (int i = 0; i < 20; i++) |
||||
{ |
||||
float angle = i / 20.0f * M_PI * 2.0f; |
||||
glVertex3f(x + r * cosf(angle), y + r * sinf(angle), z); |
||||
} |
||||
glEnd(); |
||||
} |
||||
break; |
||||
case px::GLOverlay::SOLID_CIRCLE: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
float r = getFloatValue(data, i); |
||||
|
||||
glBegin(GL_POLYGON); |
||||
for (int i = 0; i < 20; i++) |
||||
{ |
||||
float angle = i / 20.0f * M_PI * 2.0f; |
||||
glVertex3f(x + r * cosf(angle), y + r * sinf(angle), z); |
||||
} |
||||
glEnd(); |
||||
} |
||||
break; |
||||
case px::GLOverlay::SOLID_CUBE: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
float w = getFloatValue(data, i); |
||||
float h = getFloatValue(data, i); |
||||
|
||||
float w_2 = w / 2.0f; |
||||
float h_2 = h / 2.0f; |
||||
glBegin(GL_QUADS); |
||||
// face 1
|
||||
glNormal3f(1.0f, 0.0f, 0.0f); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
// face 2
|
||||
glNormal3f(0.0f, 1.0f, 0.0f); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
// face 3
|
||||
glNormal3f(0.0f, 0.0f, 1.0f); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
// face 4
|
||||
glNormal3f(-1.0f, 0.0f, 0.0f); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
// face 5
|
||||
glNormal3f(0.0f, -1.0f, 0.0f); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
// face 6
|
||||
glNormal3f(0.0f, 0.0f, -1.0f); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
|
||||
glEnd(); |
||||
} |
||||
break; |
||||
case px::GLOverlay::WIRE_CUBE: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
float w = getFloatValue(data, i); |
||||
float h = getFloatValue(data, i); |
||||
|
||||
float w_2 = w / 2.0f; |
||||
float h_2 = h / 2.0f; |
||||
// face 1
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
glEnd(); |
||||
// face 2
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
glEnd(); |
||||
// face 3
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x + w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
glEnd(); |
||||
// face 4
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z + h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
glEnd(); |
||||
// face 5
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x - w_2, y - w_2, z + h_2); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z + h_2); |
||||
glEnd(); |
||||
// face 6
|
||||
glBegin(GL_LINE_LOOP); |
||||
glVertex3f(x - w_2, y - w_2, z - h_2); |
||||
glVertex3f(x - w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y + w_2, z - h_2); |
||||
glVertex3f(x + w_2, y - w_2, z - h_2); |
||||
glEnd(); |
||||
} |
||||
break; |
||||
case px::GLOverlay::END: |
||||
glEnd(); |
||||
break; |
||||
case px::GLOverlay::VERTEX2F: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
glVertex2f(x, y); |
||||
} |
||||
break; |
||||
case px::GLOverlay::VERTEX3F: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
glVertex3f(x, y, z); |
||||
} |
||||
break; |
||||
case px::GLOverlay::ROTATEF: |
||||
{ |
||||
float angle = getFloatValue(data, i); |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
glRotatef(angle, x, y, z); |
||||
} |
||||
break; |
||||
case px::GLOverlay::TRANSLATEF: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
glTranslatef(x, y, z); |
||||
} |
||||
break; |
||||
case px::GLOverlay::SCALEF: |
||||
{ |
||||
float x = getFloatValue(data, i); |
||||
float y = getFloatValue(data, i); |
||||
float z = getFloatValue(data, i); |
||||
glScalef(x, y, z); |
||||
} |
||||
break; |
||||
case px::GLOverlay::PUSH_MATRIX: |
||||
glPushMatrix(); |
||||
break; |
||||
case px::GLOverlay::POP_MATRIX: |
||||
glPopMatrix(); |
||||
break; |
||||
case px::GLOverlay::COLOR3F: |
||||
{ |
||||
float red = getFloatValue(data, i); |
||||
float green = getFloatValue(data, i); |
||||
float blue = getFloatValue(data, i); |
||||
glColor3f(red, green, blue); |
||||
} |
||||
break; |
||||
case px::GLOverlay::COLOR4F: |
||||
{ |
||||
float red = getFloatValue(data, i); |
||||
float green = getFloatValue(data, i); |
||||
float blue = getFloatValue(data, i); |
||||
float alpha = getFloatValue(data, i); |
||||
glColor4f(red, green, blue, alpha); |
||||
} |
||||
break; |
||||
case px::GLOverlay::POINTSIZE: |
||||
glPointSize(getFloatValue(data, i)); |
||||
break; |
||||
case px::GLOverlay::LINEWIDTH: |
||||
glLineWidth(getFloatValue(data, i)); |
||||
break; |
||||
} |
||||
} |
||||
|
||||
glPopMatrix(); |
||||
} |
||||
|
||||
osg::BoundingBox |
||||
GLOverlayGeode::GLOverlayDrawable::computeBound() const |
||||
{ |
||||
return mBBox; |
||||
} |
||||
|
||||
float |
||||
GLOverlayGeode::GLOverlayDrawable::getFloatValue(const std::string& data, |
||||
size_t& mark) const |
||||
{ |
||||
char temp[4]; |
||||
for (int i = 0; i < 4; ++i) |
||||
{ |
||||
++mark; |
||||
temp[i] = data.at(mark); |
||||
} |
||||
|
||||
char *cp = &(temp[0]); |
||||
float *fp = reinterpret_cast<float *>(cp); |
||||
|
||||
return *fp; |
||||
} |
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
#ifndef GLOVERLAYGEODE_H |
||||
#define GLOVERLAYGEODE_H |
||||
|
||||
#include <mavlink_protobuf_manager.hpp> |
||||
#include <osg/Geode> |
||||
#include <QtGlobal> |
||||
|
||||
class GLOverlayGeode : public osg::Geode |
||||
{ |
||||
public: |
||||
GLOverlayGeode(); |
||||
|
||||
void setOverlay(px::GLOverlay& overlay); |
||||
|
||||
px::GLOverlay::CoordinateFrameType coordinateFrameType(void) const; |
||||
|
||||
void setMessageTimestamp(qreal timestamp); |
||||
qreal messageTimestamp(void) const; |
||||
|
||||
private: |
||||
class GLOverlayDrawable : public osg::Drawable |
||||
{ |
||||
public: |
||||
GLOverlayDrawable(); |
||||
|
||||
GLOverlayDrawable(const GLOverlayDrawable& drawable, |
||||
const osg::CopyOp& copyop = osg::CopyOp::SHALLOW_COPY); |
||||
|
||||
void setOverlay(px::GLOverlay& overlay); |
||||
|
||||
META_Object(GLOverlayDrawableApp, GLOverlayDrawable) |
||||
|
||||
virtual void drawImplementation(osg::RenderInfo&) const; |
||||
|
||||
virtual osg::BoundingBox computeBound() const; |
||||
|
||||
private: |
||||
float getFloatValue(const std::string& data, size_t& mark) const; |
||||
|
||||
px::GLOverlay mOverlay; |
||||
osg::BoundingBox mBBox; |
||||
}; |
||||
|
||||
osg::ref_ptr<GLOverlayDrawable> mDrawable; |
||||
px::GLOverlay::CoordinateFrameType mCoordinateFrameType; |
||||
qreal mMessageTimestamp; |
||||
}; |
||||
|
||||
#endif // GLOVERLAYGEODE_H
|
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,83 @@
@@ -0,0 +1,83 @@
|
||||
<?xml version='1.0'?> |
||||
<mavlink> |
||||
<include>common.xml</include> |
||||
<enums> |
||||
<enum name="SENSESOAR_MODE"> |
||||
<description> Different flight modes </description> |
||||
<entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry> |
||||
<entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry> |
||||
<entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry> |
||||
</enum> |
||||
</enums> |
||||
<messages> |
||||
<message id="170" name="OBS_POSITION"> |
||||
Position estimate of the observer in global frame |
||||
<field type="int32_t" name="lon">Longitude expressed in 1E7</field> |
||||
<field type="int32_t" name="lat">Latitude expressed in 1E7</field> |
||||
<field type="int32_t" name="alt">Altitude expressed in milimeters</field> |
||||
</message> |
||||
<message id="172" name="OBS_VELOCITY"> |
||||
velocity estimate of the observer in NED inertial frame |
||||
<field type="float[3]" name="vel">Velocity</field> |
||||
</message> |
||||
<message id="174" name="OBS_ATTITUDE"> |
||||
attitude estimate of the observer |
||||
<field type="double[4]" name="quat">Quaternion re;im</field> |
||||
</message> |
||||
<message id="176" name="OBS_WIND"> |
||||
Wind estimate in NED inertial frame |
||||
<field type="float[3]" name="wind">Wind</field> |
||||
</message> |
||||
<message id="178" name="OBS_AIR_VELOCITY"> |
||||
Estimate of the air velocity |
||||
<field type="float" name="magnitude">Air speed</field> |
||||
<field type="float" name="aoa">angle of attack</field> |
||||
<field type="float" name="slip">slip angle</field> |
||||
</message> |
||||
<message id="180" name="OBS_BIAS"> |
||||
IMU biases |
||||
<field type="float[3]" name="accBias">accelerometer bias</field> |
||||
<field type="float[3]" name="gyroBias">gyroscope bias</field> |
||||
</message> |
||||
<message id="182" name="OBS_QFF"> |
||||
estimate of the pressure at sea level |
||||
<field type="float" name="qff">Wind</field> |
||||
</message> |
||||
<message id="183" name="OBS_AIR_TEMP"> |
||||
ambient air temperature |
||||
<field type="float" name="airT">Air Temperatur</field> |
||||
</message> |
||||
<message id="184" name="FILT_ROT_VEL"> |
||||
filtered rotational velocity |
||||
<field type="float[3]" name="rotVel">rotational velocity</field> |
||||
</message> |
||||
<message id="186" name="LLC_OUT"> |
||||
low level control output |
||||
<field type="int16_t[4]" name="servoOut">Servo signal</field> |
||||
<field type="int16_t[2]" name="MotorOut">motor signal</field> |
||||
</message> |
||||
<message id="188" name="PM_ELEC"> |
||||
Power managment |
||||
<field type="float" name="PwCons">current power consumption</field> |
||||
<field type="float" name="BatStat">battery status</field> |
||||
<field type="float[3]" name="PwGen">Power generation from each module</field> |
||||
</message> |
||||
<message id="190" name="SYS_Stat"> |
||||
system status |
||||
<field type="uint8_t" name="gps">gps status</field> |
||||
<field type="uint8_t" name="act">actuator status</field> |
||||
<field type="uint8_t" name="mod">module status</field> |
||||
<field type="uint8_t" name="commRssi">module status</field> |
||||
</message> |
||||
<message id="192" name="CMD_AIRSPEED_CHNG"> |
||||
change commanded air speed |
||||
<field type="uint8_t" name="target">Target ID</field> |
||||
<field type="float" name="spCmd">commanded airspeed</field> |
||||
</message> |
||||
<message id="194" name="CMD_AIRSPEED_ACK"> |
||||
accept change of airspeed |
||||
<field type="float" name="spCmd">commanded airspeed</field> |
||||
<field type="uint8_t" name="ack">0:ack, 1:nack</field> |
||||
</message> |
||||
</messages> |
||||
</mavlink> |
Loading…
Reference in new issue