PX4 Firmware
PX4 Autopilot Software http://px4.io
PX4Accelerometer.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 
35 #include "PX4Accelerometer.hpp"
36 
38 
39 PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
40  CDev(nullptr),
41  ModuleParams(nullptr),
42  _sensor_accel_pub{ORB_ID(sensor_accel), priority},
43  _rotation{rotation}
44 {
46 
48  _sensor_accel_pub.get().scaling = 1.0f;
49 
50  // set software low pass filter for controllers
51  updateParams();
52  configure_filter(_param_imu_accel_cutoff.get());
53 }
54 
56 {
57  if (_class_device_instance != -1) {
59  }
60 }
61 
62 int
63 PX4Accelerometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
64 {
65  switch (cmd) {
66  case ACCELIOCSSCALE: {
67  // Copy offsets and scale factors in
68  accel_calibration_s cal{};
69  memcpy(&cal, (accel_calibration_s *) arg, sizeof(cal));
70 
71  _calibration_offset = matrix::Vector3f{cal.x_offset, cal.y_offset, cal.z_offset};
72  _calibration_scale = matrix::Vector3f{cal.x_scale, cal.y_scale, cal.z_scale};
73  }
74 
75  return PX4_OK;
76 
77  case DEVIOCGDEVICEID:
79 
80  default:
81  return -ENOTTY;
82  }
83 }
84 
85 void
87 {
88  // current DeviceStructure
89  union device::Device::DeviceId device_id;
90  device_id.devid = _sensor_accel_pub.get().device_id;
91 
92  // update to new device type
93  device_id.devid_s.devtype = devtype;
94 
95  // copy back to report
96  _sensor_accel_pub.get().device_id = device_id.devid;
97 }
98 
99 void
101 {
102  _sample_rate = rate;
104 }
105 
106 void
107 PX4Accelerometer::update(hrt_abstime timestamp, float x, float y, float z)
108 {
110  report.timestamp = timestamp;
111 
112  // Apply rotation (before scaling)
113  rotate_3f(_rotation, x, y, z);
114 
115  const matrix::Vector3f raw{x, y, z};
116 
117  // Apply range scale and the calibrating offset/scale
118  const matrix::Vector3f val_calibrated{(((raw * report.scaling) - _calibration_offset).emult(_calibration_scale))};
119 
120  // Filtered values
121  const matrix::Vector3f val_filtered{_filter.apply(val_calibrated)};
122 
123  // Integrated values
124  matrix::Vector3f integrated_value;
125  uint32_t integral_dt = 0;
126 
127  if (_integrator.put(timestamp, val_calibrated, integrated_value, integral_dt)) {
128 
129  // Raw values (ADC units 0 - 65535)
130  report.x_raw = x;
131  report.y_raw = y;
132  report.z_raw = z;
133 
134  report.x = val_filtered(0);
135  report.y = val_filtered(1);
136  report.z = val_filtered(2);
137 
138  report.integral_dt = integral_dt;
139  report.x_integral = integrated_value(0);
140  report.y_integral = integrated_value(1);
141  report.z_integral = integrated_value(2);
142 
143  poll_notify(POLLIN);
145  }
146 }
147 
148 void
150 {
151  PX4_INFO(ACCEL_BASE_DEVICE_PATH " device instance: %d", _class_device_instance);
152  PX4_INFO("sample rate: %d Hz", _sample_rate);
153  PX4_INFO("filter cutoff: %.3f Hz", (double)_filter.get_cutoff_freq());
154 
155  PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1),
156  (double)_calibration_scale(2));
157  PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1),
158  (double)_calibration_offset(2));
159 
160  print_message(_sensor_accel_pub.get());
161 }
uint32_t integral_dt
Definition: sensor_accel.h:59
uint64_t timestamp
Definition: sensor_accel.h:53
PX4Accelerometer(uint32_t device_id, uint8_t priority=ORB_PRIO_DEFAULT, enum Rotation rotation=ROTATION_NONE)
~PX4Accelerometer() override
void set_sample_rate(unsigned rate)
virtual int register_class_devname(const char *class_devname)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:78
void update(hrt_abstime timestamp, float x, float y, float z)
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
Definition: rotation.cpp:63
matrix::Vector3f _calibration_offset
static int32_t device_id[max_accel_sens]
math::LowPassFilter2pVector3f _filter
accel scaling factors; Vout = Vscale * (Vin + Voffset)
Definition: drv_accel.h:54
bool put(const uint64_t &timestamp, const matrix::Vector3f &val, matrix::Vector3f &integral, uint32_t &integral_dt)
Put an item into the integral.
Definition: integrator.cpp:54
struct DeviceStructure devid_s
Definition: Device.hpp:157
virtual void poll_notify(pollevent_t events)
Report new poll events.
Definition: CDev.cpp:330
#define ACCEL_BASE_DEVICE_PATH
Definition: drv_accel.h:49
Definitions for the generic base classes in the device framework.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
void set_cutoff_frequency(float sample_freq, float cutoff_freq)
enum Rotation _rotation
matrix::Vector3f _calibration_scale
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:109
void configure_filter(float cutoff_freq)
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override
Perform an ioctl operation on the device.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define ACCELIOCSSCALE
set the accel scaling constants to the structure pointed to by (arg)
Definition: drv_accel.h:73
matrix::Vector3f apply(const matrix::Vector3f &sample)
Add a new raw value to the filter.
uint32_t device_id
Definition: sensor_accel.h:55
uORB::PublicationMultiData< sensor_accel_s > _sensor_accel_pub
void set_device_type(uint8_t devtype)