QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleObjectAvoidance.cc
Go to the documentation of this file.
2#include "MAVLinkLib.h"
3#include "Vehicle.h"
4#include "ParameterManager.h"
6
7//-----------------------------------------------------------------------------
9 : QObject(parent)
10 , _vehicle(vehicle)
11{
12}
13
14//-----------------------------------------------------------------------------
15void
17{
18 //-- Collect raw data
19 if(std::isfinite(message->increment_f) && message->increment_f > 0) {
20 _increment = static_cast<qreal>(message->increment_f);
21 } else {
22 _increment = static_cast<qreal>(message->increment);
23 }
24 _minDistance = message->min_distance;
25 _maxDistance = message->max_distance;
26 _angleOffset = static_cast<qreal>(message->angle_offset);
27 if(_distances.count() == 0) {
28 for(int i = 0; i < MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN; i++) {
29 _distances.append(static_cast<int>(message->distances[i]));
30 }
31 } else {
32 for(int i = 0; i < MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN; i++) {
33 _distances[i] = static_cast<int>(message->distances[i]);
34 }
35 }
36 //-- Create a plottable grid with found objects
37 _objGrid.clear();
38 _objDistance.clear();
39 auto* sp = qobject_cast<VehicleSetpointFactGroup*>(_vehicle->setpointFactGroup());
40 qreal startAngle = sp->yaw()->rawValue().toDouble() + _angleOffset;
41 for(int i = 0; i < MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN; i++) {
42 if(_distances[i] < _maxDistance && message->distances[i] != UINT16_MAX) {
43 qreal d = static_cast<qreal>(_distances[i]);
44 d = d / static_cast<qreal>(_maxDistance);
45 qreal a = (_increment * i) - startAngle;
46 if(a < 0) a = a + 360;
47 qreal rd = (M_PI / 180.0) * a;
48 QPointF p = QPointF(d * cos(rd), d * sin(rd));
49 _objGrid.append(p);
50 _objDistance.append(d);
51 }
52 }
54}
55
56//-----------------------------------------------------------------------------
57bool
59{
60 uint8_t id = static_cast<uint8_t>(_vehicle->compId());
61 if(_vehicle->parameterManager()->parameterExists(id, kColPrevParam)) {
62 return _vehicle->parameterManager()->getParameter(id, kColPrevParam)->rawValue().toInt() >= 0;
63 }
64 return false;
65}
66
67//-----------------------------------------------------------------------------
68void
70{
71 uint8_t id = static_cast<uint8_t>(_vehicle->compId());
72 if(_vehicle->parameterManager()->parameterExists(id, kColPrevParam)) {
73 _vehicle->parameterManager()->getParameter(id, kColPrevParam)->setRawValue(minDistance);
75 }
76}
77
78//-----------------------------------------------------------------------------
79void
81{
82 uint8_t id = static_cast<uint8_t>(_vehicle->compId());
83 if(_vehicle->parameterManager()->parameterExists(id, kColPrevParam)) {
84 _vehicle->parameterManager()->getParameter(id, kColPrevParam)->setRawValue(-1);
86 }
87}
88
89//-----------------------------------------------------------------------------
90QPointF
92{
93 if(i < _objGrid.count() && i >= 0) {
94 return _objGrid[i];
95 }
96 return QPointF(0,0);
97}
98
99//-----------------------------------------------------------------------------
100qreal
102{
103 if(i < _objDistance.count() && i >= 0) {
104 return _objDistance[i];
105 }
106 return 0;
107}
struct __mavlink_obstacle_distance_t mavlink_obstacle_distance_t
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
VehicleObjectAvoidance(Vehicle *vehicle, QObject *parent=nullptr)
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)
int compId() const
Definition Vehicle.h:426
FactGroup * setpointFactGroup()
Definition Vehicle.cc:418
ParameterManager * parameterManager()
Definition Vehicle.h:573