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