PX4 Firmware
PX4 Autopilot Software http://px4.io
PX4Gyroscope.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 "PX4Gyroscope.hpp"
36 
38 
39 PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
40  CDev(nullptr),
41  ModuleParams(nullptr),
42  _sensor_gyro_pub{ORB_ID(sensor_gyro), priority},
43  _sensor_gyro_control_pub{ORB_ID(sensor_gyro_control), priority},
44  _rotation{rotation}
45 {
47 
49  _sensor_gyro_pub.get().scaling = 1.0f;
51 
52  // set software low pass filter for controllers
53  updateParams();
54  configure_filter(_param_imu_gyro_cutoff.get());
55 }
56 
58 {
59  if (_class_device_instance != -1) {
61  }
62 }
63 
64 int
65 PX4Gyroscope::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
66 {
67  switch (cmd) {
68  case GYROIOCSSCALE: {
69  // Copy offsets and scale factors in
70  gyro_calibration_s cal{};
71  memcpy(&cal, (gyro_calibration_s *) arg, sizeof(cal));
72 
73  _calibration_offset = matrix::Vector3f{cal.x_offset, cal.y_offset, cal.z_offset};
74  _calibration_scale = matrix::Vector3f{cal.x_scale, cal.y_scale, cal.z_scale};
75  }
76 
77  return PX4_OK;
78 
79  case DEVIOCGDEVICEID:
81 
82  default:
83  return -ENOTTY;
84  }
85 }
86 
87 void
89 {
90  // current DeviceStructure
91  union device::Device::DeviceId device_id;
92  device_id.devid = _sensor_gyro_pub.get().device_id;
93 
94  // update to new device type
95  device_id.devid_s.devtype = devtype;
96 
97  // copy back to report
98  _sensor_gyro_pub.get().device_id = device_id.devid;
100 }
101 
102 void
104 {
105  _sample_rate = rate;
107 }
108 
109 void
110 PX4Gyroscope::update(hrt_abstime timestamp, float x, float y, float z)
111 {
112  sensor_gyro_s &report = _sensor_gyro_pub.get();
113  report.timestamp = timestamp;
114 
115  // Apply rotation (before scaling)
116  rotate_3f(_rotation, x, y, z);
117 
118  const matrix::Vector3f raw{x, y, z};
119 
120  // Apply range scale and the calibrating offset/scale
121  const matrix::Vector3f val_calibrated{(((raw * report.scaling) - _calibration_offset).emult(_calibration_scale))};
122 
123  // Filtered values
124  const matrix::Vector3f val_filtered{_filter.apply(val_calibrated)};
125 
126 
127  // publish control data (filtered gyro) immediately
128  bool publish_control = true;
130 
131  if (_param_imu_gyro_rate_max.get() > 0) {
132  const uint64_t interval = 1e6f / _param_imu_gyro_rate_max.get();
133 
134  if (hrt_elapsed_time(&control.timestamp_sample) < interval) {
135  publish_control = false;
136  }
137  }
138 
139  if (publish_control) {
140  control.timestamp_sample = timestamp;
141  val_filtered.copyTo(control.xyz);
142  control.timestamp = hrt_absolute_time();
143  _sensor_gyro_control_pub.update(); // publish
144  }
145 
146 
147  // Integrated values
148  matrix::Vector3f integrated_value;
149  uint32_t integral_dt = 0;
150 
151  if (_integrator.put(timestamp, val_calibrated, integrated_value, integral_dt)) {
152 
153  // Raw values (ADC units 0 - 65535)
154  report.x_raw = x;
155  report.y_raw = y;
156  report.z_raw = z;
157 
158  report.x = val_filtered(0);
159  report.y = val_filtered(1);
160  report.z = val_filtered(2);
161 
162  report.integral_dt = integral_dt;
163  report.x_integral = integrated_value(0);
164  report.y_integral = integrated_value(1);
165  report.z_integral = integrated_value(2);
166 
167  poll_notify(POLLIN);
168  _sensor_gyro_pub.update(); // publish
169  }
170 }
171 
172 void
174 {
175  PX4_INFO(GYRO_BASE_DEVICE_PATH " device instance: %d", _class_device_instance);
176  PX4_INFO("sample rate: %d Hz", _sample_rate);
177  PX4_INFO("filter cutoff: %.3f Hz", (double)_filter.get_cutoff_freq());
178 
179  PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1),
180  (double)_calibration_scale(2));
181  PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1),
182  (double)_calibration_offset(2));
183 
184  print_message(_sensor_gyro_pub.get());
185  print_message(_sensor_gyro_control_pub.get());
186 }
matrix::Vector3f _calibration_scale
unsigned _sample_rate
gyro scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_gyro.h:54
void print_status()
int16_t x_raw
Definition: sensor_gyro.h:65
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
__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
int _class_device_instance
void configure_filter(float cutoff_freq)
Integrator _integrator
float x_integral
Definition: sensor_gyro.h:60
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override
Perform an ioctl operation on the device.
int16_t z_raw
Definition: sensor_gyro.h:67
int16_t y_raw
Definition: sensor_gyro.h:66
static int32_t device_id[max_accel_sens]
void set_device_type(uint8_t devtype)
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
Definitions for the generic base classes in the device framework.
float z_integral
Definition: sensor_gyro.h:62
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
void update(hrt_abstime timestamp, float x, float y, float z)
void set_cutoff_frequency(float sample_freq, float cutoff_freq)
#define GYRO_BASE_DEVICE_PATH
Definition: drv_gyro.h:49
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 set_sample_rate(unsigned rate)
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
enum Rotation _rotation
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now.
Definition: drv_hrt.h:102
float y_integral
Definition: sensor_gyro.h:61
uORB::PublicationMultiData< sensor_gyro_control_s > _sensor_gyro_control_pub
uint64_t timestamp
Definition: sensor_gyro.h:53
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
uint32_t device_id
Definition: sensor_gyro.h:55
PX4Gyroscope(uint32_t device_id, uint8_t priority=ORB_PRIO_DEFAULT, enum Rotation rotation=ROTATION_NONE)
math::LowPassFilter2pVector3f _filter
matrix::Vector3f apply(const matrix::Vector3f &sample)
Add a new raw value to the filter.
~PX4Gyroscope() override
matrix::Vector3f _calibration_offset
#define GYROIOCSSCALE
set the gyro scaling constants to (arg)
Definition: drv_gyro.h:71
uORB::PublicationMultiData< sensor_gyro_s > _sensor_gyro_pub
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
uint32_t integral_dt
Definition: sensor_gyro.h:59