Commit fc8b497e authored by LM's avatar LM

Merge branch 'v10release' of https://github.com/hengli/qgroundcontrol

parents 855c376d 1da1543d
...@@ -47,6 +47,15 @@ quint64 groundTimeMilliseconds() ...@@ -47,6 +47,15 @@ quint64 groundTimeMilliseconds()
return static_cast<quint64>(seconds + (time.time().msec())); return static_cast<quint64>(seconds + (time.time().msec()));
} }
qreal groundTimeSeconds()
{
QDateTime time = QDateTime::currentDateTime();
time = time.toUTC();
/* Return time in seconds unit */
quint64 seconds = time.toTime_t();
return static_cast<qreal>(seconds + (time.time().msec() / 1000.0));
}
float limitAngleToPMPIf(float angle) float limitAngleToPMPIf(float angle)
{ {
if (angle > -20*M_PI && angle < 20*M_PI) if (angle > -20*M_PI && angle < 20*M_PI)
......
...@@ -77,6 +77,8 @@ const QColor colorBlack(0, 0, 0); ...@@ -77,6 +77,8 @@ const QColor colorBlack(0, 0, 0);
quint64 groundTimeUsecs(); quint64 groundTimeUsecs();
/** @brief Get the current ground time in milliseconds */ /** @brief Get the current ground time in milliseconds */
quint64 groundTimeMilliseconds(); quint64 groundTimeMilliseconds();
/** @brief Get the current ground time in seconds */
qreal groundTimeSeconds();
/** @brief Returns the angle limited to -pi - pi */ /** @brief Returns the angle limited to -pi - pi */
float limitAngleToPMPIf(float angle); float limitAngleToPMPIf(float angle);
/** @brief Returns the angle limited to -pi - pi */ /** @brief Returns the angle limited to -pi - pi */
......
...@@ -31,6 +31,10 @@ ...@@ -31,6 +31,10 @@
#include "QGCMAVLinkUASFactory.h" #include "QGCMAVLinkUASFactory.h"
#include "QGC.h" #include "QGC.h"
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif
/** /**
* The default constructor will create a new MAVLink object sending heartbeats at * The default constructor will create a new MAVLink object sending heartbeats at
...@@ -220,7 +224,42 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -220,7 +224,42 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
if (protobufManager.getMessage(protobuf_msg)) if (protobufManager.getMessage(protobuf_msg))
{ {
emit extendedMessageReceived(link, protobuf_msg); const google::protobuf::Descriptor* descriptor = protobuf_msg->GetDescriptor();
if (!descriptor)
{
continue;
}
const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
if (!headerField)
{
continue;
}
const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
if (!headerDescriptor)
{
continue;
}
const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
if (!sourceSysIdField)
{
continue;
}
const google::protobuf::Reflection* reflection = protobuf_msg->GetReflection();
const google::protobuf::Message& headerMsg = reflection->GetMessage(*protobuf_msg, headerField);
const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();
int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);
UASInterface* uas = UASManager::instance()->getUASForId(source_sysid);
if (uas != NULL)
{
emit extendedMessageReceived(link, protobuf_msg);
}
} }
} }
......
...@@ -20,8 +20,20 @@ public: ...@@ -20,8 +20,20 @@ public:
QList<QVariant> getParameterValues(int component) const { QList<QVariant> getParameterValues(int component) const {
return parameters.value(component)->values(); return parameters.value(component)->values();
} }
QVariant getParameterValue(int component, const QString& parameter) const { bool getParameterValue(int component, const QString& parameter, QVariant& value) const {
return parameters.value(component)->value(parameter); if (!parameters.contains(component))
{
return false;
}
if (!parameters.value(component)->contains(parameter))
{
return false;
}
value = parameters.value(component)->value(parameter);
return true;
} }
virtual bool isParamMinKnown(const QString& param) = 0; virtual bool isParamMinKnown(const QString& param) = 0;
......
...@@ -27,6 +27,10 @@ ...@@ -27,6 +27,10 @@
#include "LinkManager.h" #include "LinkManager.h"
#include "SerialLink.h" #include "SerialLink.h"
#ifdef QGC_PROTOBUF_ENABLED
#include <google/protobuf/descriptor.h>
#endif
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id), uasId(id),
startTime(QGC::groundTimeMilliseconds()), startTime(QGC::groundTimeMilliseconds()),
...@@ -986,6 +990,41 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl ...@@ -986,6 +990,41 @@ void UAS::receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<googl
addLink(link); addLink(link);
} }
const google::protobuf::Descriptor* descriptor = message->GetDescriptor();
if (!descriptor)
{
return;
}
const google::protobuf::FieldDescriptor* headerField = descriptor->FindFieldByName("header");
if (!headerField)
{
return;
}
const google::protobuf::Descriptor* headerDescriptor = headerField->message_type();
if (!headerDescriptor)
{
return;
}
const google::protobuf::FieldDescriptor* sourceSysIdField = headerDescriptor->FindFieldByName("source_sysid");
if (!sourceSysIdField)
{
return;
}
const google::protobuf::Reflection* reflection = message->GetReflection();
const google::protobuf::Message& headerMsg = reflection->GetMessage(*message, headerField);
const google::protobuf::Reflection* headerReflection = headerMsg.GetReflection();
int source_sysid = headerReflection->GetInt32(headerMsg, sourceSysIdField);
if (source_sysid != uasId)
{
return;
}
if (message->GetTypeName() == pointCloud.GetTypeName()) if (message->GetTypeName() == pointCloud.GetTypeName())
{ {
pointCloud.CopyFrom(*message); pointCloud.CopyFrom(*message);
......
...@@ -47,6 +47,15 @@ ObstacleGroupNode::init(void) ...@@ -47,6 +47,15 @@ ObstacleGroupNode::init(void)
} }
void
ObstacleGroupNode::clear(void)
{
if (getNumChildren() > 0)
{
removeChild(0, getNumChildren());
}
}
void void
ObstacleGroupNode::update(MAV_FRAME frame, UASInterface *uas) ObstacleGroupNode::update(MAV_FRAME frame, UASInterface *uas)
{ {
...@@ -59,10 +68,7 @@ ObstacleGroupNode::update(MAV_FRAME frame, UASInterface *uas) ...@@ -59,10 +68,7 @@ ObstacleGroupNode::update(MAV_FRAME frame, UASInterface *uas)
double robotY = uas->getLocalY(); double robotY = uas->getLocalY();
double robotZ = uas->getLocalZ(); double robotZ = uas->getLocalZ();
if (getNumChildren() > 0) clear();
{
removeChild(0, getNumChildren());
}
osg::ref_ptr<osg::Geode> geode = new osg::Geode; osg::ref_ptr<osg::Geode> geode = new osg::Geode;
......
...@@ -42,6 +42,7 @@ public: ...@@ -42,6 +42,7 @@ public:
ObstacleGroupNode(); ObstacleGroupNode();
void init(void); void init(void);
void clear(void);
void update(MAV_FRAME frame, UASInterface* uas); void update(MAV_FRAME frame, UASInterface* uas);
}; };
......
...@@ -53,6 +53,7 @@ ...@@ -53,6 +53,7 @@
Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
: Q3DWidget(parent) : Q3DWidget(parent)
, uas(NULL) , uas(NULL)
, kMessageTimeout(2.0)
, mode(DEFAULT_MODE) , mode(DEFAULT_MODE)
, selectedWpIndex(-1) , selectedWpIndex(-1)
, displayLocalGrid(false) , displayLocalGrid(false)
...@@ -299,7 +300,7 @@ Pixhawk3DWidget::selectTargetHeading(void) ...@@ -299,7 +300,7 @@ Pixhawk3DWidget::selectTargetHeading(void)
p.set(cursorWorldCoords.first, cursorWorldCoords.second); p.set(cursorWorldCoords.first, cursorWorldCoords.second);
} }
target.z() = atan2(p.y() - target.y(), p.x() - target.x()); target.setW(atan2(p.y() - target.y(), p.x() - target.x()));
} }
void void
...@@ -309,6 +310,10 @@ Pixhawk3DWidget::selectTarget(void) ...@@ -309,6 +310,10 @@ Pixhawk3DWidget::selectTarget(void)
{ {
return; return;
} }
if (!uas->getParamManager())
{
return;
}
if (frame == MAV_FRAME_GLOBAL) if (frame == MAV_FRAME_GLOBAL)
{ {
...@@ -318,7 +323,14 @@ Pixhawk3DWidget::selectTarget(void) ...@@ -318,7 +323,14 @@ Pixhawk3DWidget::selectTarget(void)
getGlobalCursorPosition(cachedMousePos.x(), cachedMousePos.y(), getGlobalCursorPosition(cachedMousePos.x(), cachedMousePos.y(),
altitude); altitude);
target.set(cursorWorldCoords.first, cursorWorldCoords.second, 0.0); QVariant zTarget;
if (!uas->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
{
zTarget = -altitude;
}
target = QVector4D(cursorWorldCoords.first, cursorWorldCoords.second,
zTarget.toReal(), 0.0);
} }
else if (frame == MAV_FRAME_LOCAL_NED) else if (frame == MAV_FRAME_LOCAL_NED)
{ {
...@@ -327,7 +339,14 @@ Pixhawk3DWidget::selectTarget(void) ...@@ -327,7 +339,14 @@ Pixhawk3DWidget::selectTarget(void)
std::pair<double,double> cursorWorldCoords = std::pair<double,double> cursorWorldCoords =
getGlobalCursorPosition(cachedMousePos.x(), cachedMousePos.y(), -z); getGlobalCursorPosition(cachedMousePos.x(), cachedMousePos.y(), -z);
target.set(cursorWorldCoords.first, cursorWorldCoords.second, 0.0); QVariant zTarget;
if (!uas->getParamManager()->getParameterValue(MAV_COMP_ID_PATHPLANNER, "TARGET-ALT", zTarget))
{
zTarget = z;
}
target = QVector4D(cursorWorldCoords.first, cursorWorldCoords.second,
zTarget.toReal(), 0.0);
} }
enableTarget = true; enableTarget = true;
...@@ -340,8 +359,8 @@ Pixhawk3DWidget::setTarget(void) ...@@ -340,8 +359,8 @@ Pixhawk3DWidget::setTarget(void)
{ {
selectTargetHeading(); selectTargetHeading();
uas->setTargetPosition(target.x(), target.y(), 0.0, uas->setTargetPosition(target.x(), target.y(), target.z(),
osg::RadiansToDegrees(target.z())); osg::RadiansToDegrees(target.w()));
} }
void void
...@@ -761,7 +780,7 @@ Pixhawk3DWidget::display(void) ...@@ -761,7 +780,7 @@ Pixhawk3DWidget::display(void)
if (enableTarget) if (enableTarget)
{ {
updateTarget(robotX, robotY); updateTarget(robotX, robotY, robotZ);
} }
#ifdef QGC_PROTOBUF_ENABLED #ifdef QGC_PROTOBUF_ENABLED
...@@ -1493,20 +1512,21 @@ Pixhawk3DWidget::updateWaypoints(void) ...@@ -1493,20 +1512,21 @@ Pixhawk3DWidget::updateWaypoints(void)
} }
void void
Pixhawk3DWidget::updateTarget(double robotX, double robotY) Pixhawk3DWidget::updateTarget(double robotX, double robotY, double robotZ)
{ {
osg::PositionAttitudeTransform* pat = osg::PositionAttitudeTransform* pat =
dynamic_cast<osg::PositionAttitudeTransform*>(targetNode.get()); dynamic_cast<osg::PositionAttitudeTransform*>(targetNode.get());
pat->setPosition(osg::Vec3d(target.y() - robotY, target.x() - robotX, 0.0)); pat->setPosition(osg::Vec3d(target.y() - robotY,
pat->setAttitude(osg::Quat(target.z() - M_PI_2, osg::Vec3d(1.0f, 0.0f, 0.0f), target.x() - robotX,
-(target.z() - robotZ)));
pat->setAttitude(osg::Quat(target.w() - M_PI_2, osg::Vec3d(1.0f, 0.0f, 0.0f),
M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f), M_PI_2, osg::Vec3d(0.0f, 1.0f, 0.0f),
0.0, osg::Vec3d(0.0f, 0.0f, 1.0f))); 0.0, osg::Vec3d(0.0f, 0.0f, 1.0f)));
osg::Geode* geode = dynamic_cast<osg::Geode*>(pat->getChild(0)); osg::Geode* geode = dynamic_cast<osg::Geode*>(pat->getChild(0));
osg::ShapeDrawable* sd = dynamic_cast<osg::ShapeDrawable*>(geode->getDrawable(0)); osg::ShapeDrawable* sd = dynamic_cast<osg::ShapeDrawable*>(geode->getDrawable(0));
sd->setColor(osg::Vec4f(1.0f, 0.8f, 0.0f, 1.0f)); sd->setColor(osg::Vec4f(1.0f, 0.8f, 0.0f, 1.0f));
} }
...@@ -1607,7 +1627,14 @@ Pixhawk3DWidget::updateRGBD(double robotX, double robotY, double robotZ) ...@@ -1607,7 +1627,14 @@ Pixhawk3DWidget::updateRGBD(double robotX, double robotY, double robotZ)
void void
Pixhawk3DWidget::updateObstacles(void) Pixhawk3DWidget::updateObstacles(void)
{ {
obstacleGroupNode->update(frame, uas); if (QGC::groundTimeSeconds() - uas->getObstacleList().header().timestamp() < kMessageTimeout)
{
obstacleGroupNode->update(frame, uas);
}
else
{
obstacleGroupNode->clear();
}
} }
void void
...@@ -1628,51 +1655,54 @@ Pixhawk3DWidget::updatePath(double robotX, double robotY, double robotZ) ...@@ -1628,51 +1655,54 @@ Pixhawk3DWidget::updatePath(double robotX, double robotY, double robotZ)
osg::ref_ptr<osg::Vec3Array> vertices(new osg::Vec3Array); osg::ref_ptr<osg::Vec3Array> vertices(new osg::Vec3Array);
// find path length if (QGC::groundTimeSeconds() - path.header().timestamp() < kMessageTimeout)
float length = 0.0f;
for (int i = 0; i < path.waypoints_size() - 1; ++i)
{ {
const px::Waypoint& wp0 = path.waypoints(i); // find path length
const px::Waypoint& wp1 = path.waypoints(i+1); float length = 0.0f;
for (int i = 0; i < path.waypoints_size() - 1; ++i)
{
const px::Waypoint& wp0 = path.waypoints(i);
const px::Waypoint& wp1 = path.waypoints(i+1);
length += qgc::hypot3f(wp0.x() - wp1.x(), length += qgc::hypot3f(wp0.x() - wp1.x(),
wp0.y() - wp1.y(), wp0.y() - wp1.y(),
wp0.z() - wp1.z()); wp0.z() - wp1.z());
} }
// build path // build path
if (path.waypoints_size() > 0) if (path.waypoints_size() > 0)
{ {
const px::Waypoint& wp0 = path.waypoints(0); const px::Waypoint& wp0 = path.waypoints(0);
vertices->push_back(osg::Vec3d(wp0.y() - robotY, vertices->push_back(osg::Vec3d(wp0.y() - robotY,
wp0.x() - robotX, wp0.x() - robotX,
-(wp0.z() - robotZ))); -(wp0.z() - robotZ)));
float r, g, b; float r, g, b;
qgc::colormap("autumn", 0, r, g, b); qgc::colormap("autumn", 0, r, g, b);
colorArray->push_back(osg::Vec4d(r, g, b, 1.0f)); colorArray->push_back(osg::Vec4d(r, g, b, 1.0f));
} }
float lengthCurrent = 0.0f; float lengthCurrent = 0.0f;
for (int i = 0; i < path.waypoints_size() - 1; ++i) for (int i = 0; i < path.waypoints_size() - 1; ++i)
{ {
const px::Waypoint& wp0 = path.waypoints(i); const px::Waypoint& wp0 = path.waypoints(i);
const px::Waypoint& wp1 = path.waypoints(i+1); const px::Waypoint& wp1 = path.waypoints(i+1);
lengthCurrent += qgc::hypot3f(wp0.x() - wp1.x(), lengthCurrent += qgc::hypot3f(wp0.x() - wp1.x(),
wp0.y() - wp1.y(), wp0.y() - wp1.y(),
wp0.z() - wp1.z()); wp0.z() - wp1.z());
vertices->push_back(osg::Vec3d(wp1.y() - robotY, vertices->push_back(osg::Vec3d(wp1.y() - robotY,
wp1.x() - robotX, wp1.x() - robotX,
-(wp1.z() - robotZ))); -(wp1.z() - robotZ)));
int colorIdx = lengthCurrent / length * 127.0f; int colorIdx = lengthCurrent / length * 127.0f;
float r, g, b; float r, g, b;
qgc::colormap("autumn", colorIdx, r, g, b); qgc::colormap("autumn", colorIdx, r, g, b);
colorArray->push_back(osg::Vec4f(r, g, b, 1.0f)); colorArray->push_back(osg::Vec4f(r, g, b, 1.0f));
}
} }
geometry->setVertexArray(vertices); geometry->setVertexArray(vertices);
......
...@@ -124,7 +124,7 @@ private: ...@@ -124,7 +124,7 @@ private:
void updateImagery(double originX, double originY, double originZ, void updateImagery(double originX, double originY, double originZ,
const QString& zone); const QString& zone);
void updateWaypoints(void); void updateWaypoints(void);
void updateTarget(double robotX, double robotY); void updateTarget(double robotX, double robotY, double robotZ);
#ifdef QGC_PROTOBUF_ENABLED #ifdef QGC_PROTOBUF_ENABLED
void updateRGBD(double robotX, double robotY, double robotZ); void updateRGBD(double robotX, double robotY, double robotZ);
void updateObstacles(void); void updateObstacles(void);
...@@ -136,6 +136,8 @@ private: ...@@ -136,6 +136,8 @@ private:
void showInsertWaypointMenu(const QPoint& cursorPos); void showInsertWaypointMenu(const QPoint& cursorPos);
void showEditWaypointMenu(const QPoint& cursorPos); void showEditWaypointMenu(const QPoint& cursorPos);
const qreal kMessageTimeout; // message timeout in seconds
enum Mode { enum Mode {
DEFAULT_MODE, DEFAULT_MODE,
MOVE_WAYPOINT_POSITION_MODE, MOVE_WAYPOINT_POSITION_MODE,
...@@ -184,7 +186,7 @@ private: ...@@ -184,7 +186,7 @@ private:
QVector< osg::ref_ptr<osg::Node> > vehicleModels; QVector< osg::ref_ptr<osg::Node> > vehicleModels;
MAV_FRAME frame; MAV_FRAME frame;
osg::Vec3d target; QVector4D target;
QPoint cachedMousePos; QPoint cachedMousePos;
double lastRobotX, lastRobotY, lastRobotZ; double lastRobotX, lastRobotY, lastRobotZ;
}; };
......
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