3#include <QtCore/QObject>
4#include <QtCore/QVector>
5#include <QtCore/QPointF>
6#include <QtQmlIntegration/QtQmlIntegration>
33 Q_INVOKABLE
void stop ();
35 Q_INVOKABLE QPointF
grid (
int i);
38 bool available () {
return _distances.count() > 0; }
53 QList<int> _distances;
54 QVector<QPointF>_objGrid;
55 QVector<qreal> _objDistance;
59 qreal _angleOffset = 0;
62 static constexpr const char* kColPrevParam =
"CP_DIST";
struct __mavlink_obstacle_distance_t mavlink_obstacle_distance_t
void update(mavlink_obstacle_distance_t *message)
void objectAvoidanceChanged()
qreal angleOffset() const
Q_INVOKABLE QPointF grid(int i)
Q_INVOKABLE void start(int minDistance)
Q_INVOKABLE qreal distance(int i)