voted_sensors_update.h
6.66 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
/****************************************************************************
*
* Copyright (c) 2016-2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/**
* @file voted_sensors_update.h
*
* @author Beat Kueng <beat-kueng@gmx.net>
*/
#include "data_validator/DataValidator.hpp"
#include "data_validator/DataValidatorGroup.hpp"
#include <px4_platform_common/module_params.h>
#include <drivers/drv_hrt.h>
#include <mathlib/mathlib.h>
#include <matrix/math.hpp>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_gyro.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/sensors_status_imu.h>
#include <uORB/topics/sensor_selection.h>
#include <uORB/topics/vehicle_imu.h>
#include <uORB/topics/vehicle_imu_status.h>
namespace sensors
{
static constexpr uint8_t MAX_SENSOR_COUNT = 4;
/**
** class VotedSensorsUpdate
*
* Handling of sensor updates with voting
*/
class VotedSensorsUpdate : public ModuleParams
{
public:
/**
* @param parameters parameter values. These do not have to be initialized when constructing this object.
* Only when calling init(), they have to be initialized.
*/
VotedSensorsUpdate(bool hil_enabled, uORB::SubscriptionCallbackWorkItem(&vehicle_imu_sub)[MAX_SENSOR_COUNT]);
/**
* initialize subscriptions etc.
* @return 0 on success, <0 otherwise
*/
int init(sensor_combined_s &raw);
/**
* This tries to find new sensor instances. This is called from init(), then it can be called periodically.
*/
void initializeSensors();
void printStatus();
/**
* call this whenever parameters got updated. Make sure to have initializeSensors() called at least
* once before calling this.
*/
void parametersUpdate();
/**
* read new sensor data
*/
void sensorsPoll(sensor_combined_s &raw);
/**
* set the relative timestamps of each sensor timestamp, based on the last sensorsPoll,
* so that the data can be published.
*/
void setRelativeTimestamps(sensor_combined_s &raw);
private:
static constexpr uint8_t DEFAULT_PRIORITY = 50;
struct SensorData {
SensorData() = delete;
explicit SensorData(ORB_ID meta) : subscription{{meta, 0}, {meta, 1}, {meta, 2}, {meta, 3}} {}
uORB::Subscription subscription[MAX_SENSOR_COUNT]; /**< raw sensor data subscription */
DataValidatorGroup voter{1};
unsigned int last_failover_count{0};
int32_t priority[MAX_SENSOR_COUNT] {};
int32_t priority_configured[MAX_SENSOR_COUNT] {};
uint8_t last_best_vote{0}; /**< index of the latest best vote */
uint8_t subscription_count{0};
bool advertised[MAX_SENSOR_COUNT] {false, false, false};
};
void initSensorClass(SensorData &sensor_data, uint8_t sensor_count_max);
/**
* Poll IMU for updated data.
*
* @param raw Combined sensor data structure into which
* data should be returned.
*/
void imuPoll(sensor_combined_s &raw);
/**
* Check & handle failover of a sensor
* @return true if a switch occured (could be for a non-critical reason)
*/
bool checkFailover(SensorData &sensor, const char *sensor_name);
/**
* Calculates the magnitude in m/s/s of the largest difference between each accelerometer vector and the mean of all vectors
*/
void calcAccelInconsistency();
/**
* Calculates the magnitude in rad/s of the largest difference between each gyro vector and the mean of all vectors
*/
void calcGyroInconsistency();
SensorData _accel{ORB_ID::sensor_accel};
SensorData _gyro{ORB_ID::sensor_gyro};
hrt_abstime _last_error_message{0};
orb_advert_t _mavlink_log_pub{nullptr};
uORB::Publication<sensor_selection_s> _sensor_selection_pub{ORB_ID(sensor_selection)}; /**< handle to the sensor selection uORB topic */
uORB::Publication<sensors_status_imu_s> _sensors_status_imu_pub{ORB_ID(sensors_status_imu)};
uORB::SubscriptionCallbackWorkItem(&_vehicle_imu_sub)[MAX_SENSOR_COUNT];
uORB::SubscriptionMultiArray<vehicle_imu_status_s, MAX_SENSOR_COUNT> _vehicle_imu_status_subs{ORB_ID::vehicle_imu_status};
uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)};
sensor_combined_s _last_sensor_data[MAX_SENSOR_COUNT] {}; /**< latest sensor data from all sensors instances */
const bool _hil_enabled{false}; /**< is hardware-in-the-loop mode enabled? */
bool _selection_changed{true}; /**< true when a sensor selection has changed and not been published */
matrix::Vector3f _accel_diff[MAX_SENSOR_COUNT] {}; /**< filtered accel differences between IMU units (m/s/s) */
matrix::Vector3f _gyro_diff[MAX_SENSOR_COUNT] {}; /**< filtered gyro differences between IMU uinits (rad/s) */
uint32_t _accel_device_id[MAX_SENSOR_COUNT] {}; /**< accel driver device id for each uorb instance */
uint32_t _gyro_device_id[MAX_SENSOR_COUNT] {}; /**< gyro driver device id for each uorb instance */
uint64_t _last_accel_timestamp[MAX_SENSOR_COUNT] {}; /**< latest full timestamp */
sensor_selection_s _selection {}; /**< struct containing the sensor selection to be published to the uORB */
DEFINE_PARAMETERS(
(ParamBool<px4::params::SENS_IMU_MODE>) _param_sens_imu_mode
)
};
} /* namespace sensors */