APM:Libraries
BatchSampler.cpp
Go to the documentation of this file.
1 #include "AP_InertialSensor.h"
2 #include <GCS_MAVLink/GCS.h>
3 
4 // Class level parameters
6  // @Param: BAT_CNT
7  // @DisplayName: sample count per batch
8  // @Description: Number of samples to take when logging streams of IMU sensor readings. Will be rounded down to a multiple of 32.
9  // @User: Advanced
10  // @Increment: 32
11  AP_GROUPINFO("BAT_CNT", 1, AP_InertialSensor::BatchSampler, _required_count, 1024),
12 
13  // @Param: BAT_MASK
14  // @DisplayName: Sensor Bitmask
15  // @Description: Bitmap of which IMUs to log batch data for
16  // @User: Advanced
17  // @Values: 0:None,1:First IMU,255:All
18  // @Bitmask: 0:IMU1,1:IMU2,2:IMU3
20 
21  // @Param: BAT_OPT
22  // @DisplayName: Batch Logging Options Mask
23  // @Description: Options for the BatchSampler
24  // @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP)
25  // @User: Advanced
26  AP_GROUPINFO("BAT_OPT", 3, AP_InertialSensor::BatchSampler, _batch_options_mask, 0),
27 
28  // @Param: BAT_LGIN
29  // @DisplayName: logging interval
30  // @Description: Interval between pushing samples to the DataFlash log
31  // @Units: ms
32  // @Increment: 10
33  AP_GROUPINFO("BAT_LGIN", 4, AP_InertialSensor::BatchSampler, push_interval_ms, 20),
34 
35  // @Param: BAT_LGCT
36  // @DisplayName: logging count
37  // @Description: Number of samples to push to count every @PREFIX@BAT_LGIN
38  // @Increment: 1
39  AP_GROUPINFO("BAT_LGCT", 5, AP_InertialSensor::BatchSampler, samples_per_msg, 32),
40 
42 };
43 
44 
45 extern const AP_HAL::HAL& hal;
47 {
48  if (_sensor_mask == 0) {
49  return;
50  }
51  if (_required_count <= 0) {
52  return;
53  }
54 
55  _required_count -= _required_count % 32; // round down to nearest multiple of 32
56 
57  const uint32_t total_allocation = 3*_required_count*sizeof(uint16_t);
58  gcs().send_text(MAV_SEVERITY_DEBUG, "INS: alloc %u bytes for ISB (free=%u)", total_allocation, hal.util->available_memory());
59 
60  data_x = (int16_t*)calloc(_required_count, sizeof(int16_t));
61  data_y = (int16_t*)calloc(_required_count, sizeof(int16_t));
62  data_z = (int16_t*)calloc(_required_count, sizeof(int16_t));
63  if (data_x == nullptr || data_y == nullptr || data_z == nullptr) {
64  free(data_x);
65  free(data_y);
66  free(data_z);
67  data_x = nullptr;
68  data_y = nullptr;
69  data_z = nullptr;
70  gcs().send_text(MAV_SEVERITY_WARNING, "Failed to allocate %u bytes for IMU batch sampling", total_allocation);
71  return;
72  }
73 
75 
76  initialised = true;
77 }
78 
80 {
81  if (_sensor_mask == 0) {
82  return;
83  }
85 }
86 
88 {
91  return;
92  }
93  const uint8_t bit = (1<<instance);
94  switch (type) {
97  break;
100  break;
101  }
102 }
103 
105 {
106  if (_sensor_mask == 0) {
107  // should not have been called
108  return;
109  }
110  if ((1U<<instance) > (uint8_t)_sensor_mask) {
111  // should only ever happen if user resets _sensor_mask
112  instance = 0;
113  }
114 
115  if (type == IMU_SENSOR_TYPE_ACCEL) {
116  // we have logged accelerometers, now log gyros:
120  return;
121  }
122 
123  // log for accel sensor:
125 
126  // move to next IMU backend:
127 
128  // we assume the number of gyros and accels is the same, taking
129  // this minimum stops us doing bad things if that isn't true:
130  const uint8_t _count = MIN(_imu._accel_count, _imu._gyro_count);
131 
132  // find next backend instance to log:
133  bool haveinstance = false;
134  for (uint8_t i=instance+1; i<_count; i++) {
135  if (_sensor_mask & (1U<<i)) {
136  instance = i;
137  haveinstance = true;
138  break;
139  }
140  }
141  if (!haveinstance) {
142  for (uint8_t i=0; i<=instance; i++) {
143  if (_sensor_mask & (1U<<i)) {
144  instance = i;
145  haveinstance = true;
146  break;
147  }
148  }
149  }
150  if (!haveinstance) {
151  // should not happen!
152 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
153  abort();
154 #endif
155  instance = 0;
156  return;
157  }
158 
161 }
162 
164 {
165  if (!initialised) {
166  return;
167  }
168  if (_sensor_mask == 0) {
169  return;
170  }
172  // insuffucient data to pack a packet
173  return;
174  }
175  if (AP_HAL::millis() - last_sent_ms < (uint16_t)push_interval_ms) {
176  // avoid flooding DataFlash's buffer
177  return;
178  }
180  if (dataflash == nullptr) {
181  // should not have been called
182  return;
183  }
184 
185  // possibly send isb header:
186  if (!isbh_sent && data_read_offset == 0) {
187  float sample_rate = 0; // avoid warning about uninitialised values
188  switch(type) {
190  sample_rate = _imu._gyro_raw_sample_rates[instance];
192  sample_rate *= _imu._gyro_over_sampling[instance];
193  }
194  break;
196  sample_rate = _imu._accel_raw_sample_rates[instance];
198  sample_rate *= _imu._accel_over_sampling[instance];
199  }
200  break;
201  }
202  if (!dataflash->Log_Write_ISBH(isb_seqnum,
203  type,
204  instance,
205  multiplier,
208  sample_rate)) {
209  // buffer full?
210  return;
211  }
212  isbh_sent = true;
213  }
214  // pack and send a data packet:
215  if (!dataflash->Log_Write_ISBD(isb_seqnum,
218  &data_y[data_read_offset],
219  &data_z[data_read_offset])) {
220  // maybe later?!
221  return;
222  }
223  data_read_offset += samples_per_msg;
225  if (data_read_offset >= _required_count) {
226  // that was the last one. Clean up:
227  data_read_offset = 0;
228  isb_seqnum++;
229  isbh_sent = false;
230  // rotate to next instance:
232  data_write_offset = 0; // unlocks writing process
233  }
234 }
235 
237 {
238  if (_sensor_mask == 0) {
239  return false;
240  }
241  if (!initialised) {
242  return false;
243  }
244  if (_instance != instance) {
245  return false;
246  }
247  if (_type != type) {
248  return false;
249  }
251  return false;
252  }
254  if (dataflash == nullptr) {
255  return false;
256  }
257 #define MASK_LOG_ANY 0xFFFF
258  if (!dataflash->should_log(MASK_LOG_ANY)) {
259  return false;
260  }
261  return true;
262 }
263 
264 void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample)
265 {
266  if (!should_log(_instance, _type)) {
267  return;
268  }
269  if (data_write_offset == 0) {
270  measurement_started_us = sample_us;
271  }
272 
276 
277  data_write_offset++; // may unblock the reading process
278 }
virtual uint32_t available_memory(void)
Definition: Util.h:121
static const struct AP_Param::GroupInfo var_info[]
AP_InertialSensor::IMU_SENSOR_TYPE type
Interface definition for the various Ground Control System.
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float _accel_raw_sample_rates[INS_MAX_INSTANCES]
AP_HAL::Util * util
Definition: HAL.h:115
bool should_log(uint8_t instance, IMU_SENSOR_TYPE type)
GCS & gcs()
void * calloc(size_t nmemb, size_t size)
Definition: malloc.c:76
#define MIN(a, b)
Definition: usb_conf.h:215
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES]
bool Log_Write_ISBH(uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, uint8_t instance, uint16_t multiplier, uint16_t sample_count, uint64_t sample_us, float sample_rate_hz)
Definition: DataFlash.cpp:919
void sample(uint8_t instance, IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &sample)
float _gyro_raw_sample_rates[INS_MAX_INSTANCES]
uint8_t _gyro_over_sampling[INS_MAX_INSTANCES]
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
const AP_InertialSensor & _imu
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define MASK_LOG_ANY
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES]
void free(void *ptr)
Definition: malloc.c:81
#define DEFAULT_IMU_LOG_BAT_MASK
bool Log_Write_ISBD(uint16_t isb_seqno, uint16_t seqno, const int16_t x[32], const int16_t y[32], const int16_t z[32])
Definition: DataFlash.cpp:952
uint8_t _accel_sensor_rate_sampling_enabled
uint8_t _accel_over_sampling[INS_MAX_INSTANCES]
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
uint8_t _gyro_sensor_rate_sampling_enabled