QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleObjectAvoidance.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QVector>
5#include <QtCore/QPointF>
6#include <QtQmlIntegration/QtQmlIntegration>
7
8#include "MAVLinkLib.h"
9
10class Vehicle;
11
12class VehicleObjectAvoidance : public QObject
13{
14 Q_OBJECT
15 QML_ELEMENT
16 QML_UNCREATABLE("")
17public:
18 explicit VehicleObjectAvoidance(Vehicle* vehicle, QObject* parent = nullptr);
19
20 Q_PROPERTY(bool available READ available NOTIFY objectAvoidanceChanged)
21 Q_PROPERTY(bool enabled READ enabled NOTIFY objectAvoidanceChanged)
22 Q_PROPERTY(QList<int> distances READ distances NOTIFY objectAvoidanceChanged)
23 Q_PROPERTY(qreal increment READ increment NOTIFY objectAvoidanceChanged)
24 Q_PROPERTY(int minDistance READ minDistance NOTIFY objectAvoidanceChanged)
25 Q_PROPERTY(int maxDistance READ maxDistance NOTIFY objectAvoidanceChanged)
26 Q_PROPERTY(qreal angleOffset READ angleOffset NOTIFY objectAvoidanceChanged)
27 Q_PROPERTY(int gridSize READ gridSize NOTIFY objectAvoidanceChanged)
28
29 //-- Start collision avoidance. Argument is minimum distance the vehicle should keep to all obstacles
30 Q_INVOKABLE void start (int minDistance);
31 //-- Stop collision avoidance.
32 Q_INVOKABLE void stop ();
33 //-- Object locations (in relationship to vehicle)
34 Q_INVOKABLE QPointF grid (int i);
35 Q_INVOKABLE qreal distance(int i);
36
37 bool available () { return _distances.count() > 0; }
38 bool enabled ();
39 QList<int> distances () { return _distances; }
40 qreal increment () const{ return _increment; }
41 int minDistance () const{ return _minDistance; }
42 int maxDistance () const{ return _maxDistance; }
43 qreal angleOffset () const{ return _angleOffset; }
44 int gridSize () { return _objGrid.count(); }
45
46 void update (mavlink_obstacle_distance_t* message);
47
48signals:
50
51private:
52 QList<int> _distances;
53 QVector<QPointF>_objGrid;
54 QVector<qreal> _objDistance;
55 qreal _increment = 0;
56 int _minDistance = 0;
57 int _maxDistance = 0;
58 qreal _angleOffset = 0;
59 Vehicle* _vehicle = nullptr;
60
61 static constexpr const char* kColPrevParam = "CP_DIST";
62};
void update(mavlink_obstacle_distance_t *message)