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
9#include "QGCMAVLinkTypes.h"
10
11class Vehicle;
12
13class VehicleObjectAvoidance : public QObject
14{
15 Q_OBJECT
16 QML_ELEMENT
17 QML_UNCREATABLE("")
18public:
19 explicit VehicleObjectAvoidance(Vehicle* vehicle, QObject* parent = nullptr);
20
21 Q_PROPERTY(bool available READ available NOTIFY objectAvoidanceChanged)
22 Q_PROPERTY(bool enabled READ enabled NOTIFY objectAvoidanceChanged)
23 Q_PROPERTY(QList<int> distances READ distances NOTIFY objectAvoidanceChanged)
24 Q_PROPERTY(qreal increment READ increment NOTIFY objectAvoidanceChanged)
25 Q_PROPERTY(int minDistance READ minDistance NOTIFY objectAvoidanceChanged)
26 Q_PROPERTY(int maxDistance READ maxDistance NOTIFY objectAvoidanceChanged)
27 Q_PROPERTY(qreal angleOffset READ angleOffset NOTIFY objectAvoidanceChanged)
28 Q_PROPERTY(int gridSize READ gridSize NOTIFY objectAvoidanceChanged)
29
30 //-- Start collision avoidance. Argument is minimum distance the vehicle should keep to all obstacles
31 Q_INVOKABLE void start (int minDistance);
32 //-- Stop collision avoidance.
33 Q_INVOKABLE void stop ();
34 //-- Object locations (in relationship to vehicle)
35 Q_INVOKABLE QPointF grid (int i);
36 Q_INVOKABLE qreal distance(int i);
37
38 bool available () { return _distances.count() > 0; }
39 bool enabled ();
40 QList<int> distances () { return _distances; }
41 qreal increment () const{ return _increment; }
42 int minDistance () const{ return _minDistance; }
43 int maxDistance () const{ return _maxDistance; }
44 qreal angleOffset () const{ return _angleOffset; }
45 int gridSize () { return _objGrid.count(); }
46
47 void update (mavlink_obstacle_distance_t* message);
48
49signals:
51
52private:
53 QList<int> _distances;
54 QVector<QPointF>_objGrid;
55 QVector<qreal> _objDistance;
56 qreal _increment = 0;
57 int _minDistance = 0;
58 int _maxDistance = 0;
59 qreal _angleOffset = 0;
60 Vehicle* _vehicle = nullptr;
61
62 static constexpr const char* kColPrevParam = "CP_DIST";
63};
struct __mavlink_obstacle_distance_t mavlink_obstacle_distance_t
void update(mavlink_obstacle_distance_t *message)
Q_INVOKABLE QPointF grid(int i)
Q_INVOKABLE void start(int minDistance)
Q_INVOKABLE qreal distance(int i)