基于QGC版本 V3.1.3
一,点击上传任务时,通过 qml调用 MissionController sendToVehicle 函数。
void MissionController::sendToVehicle(QmlObjectListModel *listObstacle)
{
if (_activeVehicle) {
// Convert to MissionItems so we can send to vehicle
QList<MissionItem*> missionItems;
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
if (visualItem->isSimpleItem()) {
missionItems.append(new MissionItem(qobject_cast<SimpleMissionItem*>(visualItem)->missionItem()));
} else {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
QmlObjectListModel* complexMissionItems = complexItem->getMissionItems();//获取航点
for (int j=0; j<complexMissionItems->count(); j++) {
missionItems.append(new MissionItem(*qobject_cast<MissionItem*>(complexMissionItems->get(j))));
}
delete complexMissionItems;
}
}
_activeVehicle->missionManager()->writeMissionItems(missionItems);
_visualItems->setDirty(false);
for (int i=0; i<missionItems.count(); i++) {
delete missionItems[i];
}
}
二,
(1),任务分为 两种,简单任务(SimpleMissionItem) 和复杂任务(ComplexMissionItem),两者均继承自 VisualMissionItem 。
而航测 具体任务 则继承自 ComplexMissionItem 。
(2),上传任务时 每个简单任务 对应一个 MissionItem,而每个复杂任务对应多个 MissionItem。
MissionItem负责将具体的 mavlink 指令进行封装。
三,关于航点序号的计算。
(1),简单任务,调用 insertSimpleMissionItem ,先计算序号 _nextSequenceNumber(),插入任务后 再调用 _recalcAll();
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
if (_visualItems->count() == 1) {
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
}
newItem->setDefaultsForCommand();
if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
double lastValue;
MAV_FRAME lastFrame;
if (_findLastAcceptanceRadius(&lastValue)) {
newItem->missionItem().setParam2(lastValue);
}
if (_findLastAltitude(&lastValue, &lastFrame)) {
newItem->missionItem().setFrame(lastFrame);
newItem->missionItem().setParam7(lastValue);
}
}
_visualItems->insert(i, newItem);
_recalcAll();
return newItem->sequenceNumber();
}
(2)复杂任务,调用 insertComplexMissionItem,先计算序号 _nextSequenceNumber(),插入任务后 再调用 _recalcAll();
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i,int index)
{
int sequenceNumber = _nextSequenceNumber();
bool isSurvey=true;
if(index==0)
isSurvey=false;
else
isSurvey=true;
qDebug()<<"insertComplexMissionItem"<<isSurvey<<index;
VisualMissionItem *newItem=NULL;
if(isSurvey)
{
newItem = new SurveyMissionItem(_activeVehicle, this);
}else
newItem = new PlantProtectionMissionItem(_activeVehicle,this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
_initVisualItem(newItem);
_visualItems->insert(i, newItem);
_complexItems->append(newItem);
_recalcAll();
return newItem->sequenceNumber();
}
(3),每个点 分配一个序号
int MissionController::_nextSequenceNumber(void)
{
if (_visualItems->count() == 0) {
qWarning() << "Internal error: Empty visual item list";
return 0;
} else {
VisualMissionItem* lastItem = qobject_cast<VisualMissionItem*>(_visualItems->get(_visualItems->count() - 1));
if (lastItem->isSimpleItem()) {
return lastItem->sequenceNumber() + 1;
} else {
return qobject_cast<ComplexMissionItem*>(lastItem)->lastSequenceNumber() + 1;
}
}
}
void MissionController::_recalcAll(void)
{
_recalcSequence();
_recalcChildItems();
_recalcWaypointLines();
}
void MissionController::_recalcSequence(void)
{
// Setup ascending sequence numbers for all visual items
int sequenceNumber = 0;
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
item->setSequenceNumber(sequenceNumber++);
if (!item->isSimpleItem()) {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
if (complexItem) {
sequenceNumber = complexItem->lastSequenceNumber() + 1;
} else {
qWarning() << "isSimpleItem == false, yet not ComplexMissionItem";
}
}
}
}