12 changed files with 826 additions and 14 deletions
@ -0,0 +1,34 @@
@@ -0,0 +1,34 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2018 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(drivers_accelerometer PX4Accelerometer.cpp) |
@ -0,0 +1,150 @@
@@ -0,0 +1,150 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include "PX4Accelerometer.hpp" |
||||
|
||||
#include <lib/drivers/device/Device.hpp> |
||||
|
||||
PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) : |
||||
CDev(nullptr), |
||||
ModuleParams(nullptr), |
||||
_sensor_accel_pub{ORB_ID(sensor_accel), priority}, |
||||
_rotation{get_rot_matrix(rotation)} |
||||
{ |
||||
_class_device_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); |
||||
|
||||
_sensor_accel_pub.get().device_id = device_id; |
||||
_sensor_accel_pub.get().scaling = 1.0f; |
||||
|
||||
// set software low pass filter for controllers
|
||||
updateParams(); |
||||
configure_filter(_filter_cutoff.get()); |
||||
|
||||
// force initial publish to allocate uORB buffer
|
||||
// TODO: can be removed once all drivers are in threads
|
||||
_sensor_accel_pub.update(); |
||||
} |
||||
|
||||
PX4Accelerometer::~PX4Accelerometer() |
||||
{ |
||||
if (_class_device_instance != -1) { |
||||
unregister_class_devname(ACCEL_BASE_DEVICE_PATH, _class_device_instance); |
||||
} |
||||
} |
||||
|
||||
int PX4Accelerometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) |
||||
{ |
||||
switch (cmd) { |
||||
case ACCELIOCSSCALE: { |
||||
// Copy offsets and scale factors in
|
||||
accel_calibration_s cal{}; |
||||
memcpy(&cal, (accel_calibration_s *) arg, sizeof(cal)); |
||||
|
||||
_calibration_offset = matrix::Vector3f{cal.x_offset, cal.y_offset, cal.z_offset}; |
||||
_calibration_scale = matrix::Vector3f{cal.x_scale, cal.y_scale, cal.z_scale}; |
||||
} |
||||
|
||||
return PX4_OK; |
||||
|
||||
case DEVIOCGDEVICEID: |
||||
return _sensor_accel_pub.get().device_id; |
||||
|
||||
default: |
||||
return -ENOTTY; |
||||
} |
||||
} |
||||
|
||||
void PX4Accelerometer::set_device_type(uint8_t devtype) |
||||
{ |
||||
// current DeviceStructure
|
||||
union device::Device::DeviceId device_id; |
||||
device_id.devid = _sensor_accel_pub.get().device_id; |
||||
|
||||
// update to new device type
|
||||
device_id.devid_s.devtype = devtype; |
||||
|
||||
// copy back to report
|
||||
_sensor_accel_pub.get().device_id = device_id.devid; |
||||
} |
||||
|
||||
void PX4Accelerometer::update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z) |
||||
{ |
||||
sensor_accel_s &report = _sensor_accel_pub.get(); |
||||
report.timestamp = timestamp; |
||||
|
||||
// Apply rotation, range scale, and the calibrating offset/scale
|
||||
const matrix::Vector3f val_raw{(float)x, (float)y, (float)z}; |
||||
const matrix::Vector3f val_calibrated{ _rotation *(((val_raw * report.scaling) - _calibration_offset).emult(_calibration_scale))}; |
||||
|
||||
// Filtered values
|
||||
const matrix::Vector3f val_filtered{_filter.apply(val_calibrated)}; |
||||
|
||||
// Integrated values
|
||||
matrix::Vector3f integrated_value; |
||||
uint32_t integral_dt = 0; |
||||
|
||||
if (_integrator.put(timestamp, val_calibrated, integrated_value, integral_dt)) { |
||||
|
||||
// Raw values (ADC units 0 - 65535)
|
||||
report.x_raw = x; |
||||
report.y_raw = y; |
||||
report.z_raw = z; |
||||
|
||||
report.x = val_filtered(0); |
||||
report.y = val_filtered(1); |
||||
report.z = val_filtered(2); |
||||
|
||||
report.integral_dt = integral_dt; |
||||
report.x_integral = integrated_value(0); |
||||
report.y_integral = integrated_value(1); |
||||
report.z_integral = integrated_value(2); |
||||
|
||||
poll_notify(POLLIN); |
||||
_sensor_accel_pub.update(); |
||||
} |
||||
} |
||||
|
||||
void PX4Accelerometer::print_status() |
||||
{ |
||||
PX4_INFO(ACCEL_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); |
||||
PX4_INFO("sample rate: %d Hz", _sample_rate); |
||||
PX4_INFO("filter cutoff: %.3f Hz", (double)_filter.get_cutoff_freq()); |
||||
|
||||
PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1), |
||||
(double)_calibration_scale(2)); |
||||
PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1), |
||||
(double)_calibration_offset(2)); |
||||
|
||||
print_message(_sensor_accel_pub.get()); |
||||
} |
@ -0,0 +1,88 @@
@@ -0,0 +1,88 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include <drivers/device/integrator.h> |
||||
#include <drivers/drv_accel.h> |
||||
#include <drivers/drv_hrt.h> |
||||
#include <lib/cdev/CDev.hpp> |
||||
#include <lib/conversion/rotation.h> |
||||
#include <mathlib/math/filter/LowPassFilter2pVector3f.hpp> |
||||
#include <px4_module_params.h> |
||||
#include <uORB/uORB.h> |
||||
#include <uORB/Publication.hpp> |
||||
#include <uORB/topics/sensor_accel.h> |
||||
|
||||
class PX4Accelerometer : public cdev::CDev, public ModuleParams |
||||
{ |
||||
|
||||
public: |
||||
PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Rotation rotation); |
||||
~PX4Accelerometer() override; |
||||
|
||||
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override; |
||||
|
||||
void set_device_type(uint8_t devtype); |
||||
void set_error_count(uint64_t error_count) { _sensor_accel_pub.get().error_count = error_count; } |
||||
void set_scale(float scale) { _sensor_accel_pub.get().scaling = scale; } |
||||
void set_temperature(float temperature) { _sensor_accel_pub.get().temperature = temperature; } |
||||
|
||||
void set_sample_rate(unsigned rate) { _sample_rate = rate; } |
||||
|
||||
void configure_filter(float cutoff_freq) { _filter.set_cutoff_frequency(_sample_rate, cutoff_freq); } |
||||
|
||||
void update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z); |
||||
|
||||
void print_status(); |
||||
|
||||
private: |
||||
|
||||
uORB::Publication<sensor_accel_s> _sensor_accel_pub; |
||||
|
||||
math::LowPassFilter2pVector3f _filter{1000, 100}; |
||||
Integrator _integrator{4000, false}; |
||||
|
||||
const matrix::Dcmf _rotation; |
||||
|
||||
matrix::Vector3f _calibration_scale{1.0f, 1.0f, 1.0f}; |
||||
matrix::Vector3f _calibration_offset{0.0f, 0.0f, 0.0f}; |
||||
|
||||
int _class_device_instance{-1}; |
||||
|
||||
unsigned _sample_rate{1000}; |
||||
|
||||
DEFINE_PARAMETERS( |
||||
(ParamFloat<px4::params::IMU_ACCEL_CUTOFF>) _filter_cutoff |
||||
) |
||||
|
||||
}; |
@ -0,0 +1,34 @@
@@ -0,0 +1,34 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2018 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(drivers_gyroscope PX4Gyroscope.cpp) |
@ -0,0 +1,150 @@
@@ -0,0 +1,150 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include "PX4Gyroscope.hpp" |
||||
|
||||
#include <lib/drivers/device/Device.hpp> |
||||
|
||||
PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation rotation) : |
||||
CDev(nullptr), |
||||
ModuleParams(nullptr), |
||||
_sensor_gyro_pub{ORB_ID(sensor_gyro), priority}, |
||||
_rotation{get_rot_matrix(rotation)} |
||||
{ |
||||
_class_device_instance = register_class_devname(GYRO_BASE_DEVICE_PATH); |
||||
|
||||
_sensor_gyro_pub.get().device_id = device_id; |
||||
_sensor_gyro_pub.get().scaling = 1.0f; |
||||
|
||||
// set software low pass filter for controllers
|
||||
updateParams(); |
||||
configure_filter(_filter_cutoff.get()); |
||||
|
||||
// force initial publish to allocate uORB buffer
|
||||
// TODO: can be removed once all drivers are in threads
|
||||
_sensor_gyro_pub.update(); |
||||
} |
||||
|
||||
PX4Gyroscope::~PX4Gyroscope() |
||||
{ |
||||
if (_class_device_instance != -1) { |
||||
unregister_class_devname(GYRO_BASE_DEVICE_PATH, _class_device_instance); |
||||
} |
||||
} |
||||
|
||||
int PX4Gyroscope::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) |
||||
{ |
||||
switch (cmd) { |
||||
case GYROIOCSSCALE: { |
||||
// Copy offsets and scale factors in
|
||||
gyro_calibration_s cal{}; |
||||
memcpy(&cal, (gyro_calibration_s *) arg, sizeof(cal)); |
||||
|
||||
_calibration_offset = matrix::Vector3f{cal.x_offset, cal.y_offset, cal.z_offset}; |
||||
_calibration_scale = matrix::Vector3f{cal.x_scale, cal.y_scale, cal.z_scale}; |
||||
} |
||||
|
||||
return PX4_OK; |
||||
|
||||
case DEVIOCGDEVICEID: |
||||
return _sensor_gyro_pub.get().device_id; |
||||
|
||||
default: |
||||
return -ENOTTY; |
||||
} |
||||
} |
||||
|
||||
void PX4Gyroscope::set_device_type(uint8_t devtype) |
||||
{ |
||||
// current DeviceStructure
|
||||
union device::Device::DeviceId device_id; |
||||
device_id.devid = _sensor_gyro_pub.get().device_id; |
||||
|
||||
// update to new device type
|
||||
device_id.devid_s.devtype = devtype; |
||||
|
||||
// copy back to report
|
||||
_sensor_gyro_pub.get().device_id = device_id.devid; |
||||
} |
||||
|
||||
void PX4Gyroscope::update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z) |
||||
{ |
||||
sensor_gyro_s &report = _sensor_gyro_pub.get(); |
||||
report.timestamp = timestamp; |
||||
|
||||
// Apply rotation, range scale, and the calibrating offset/scale
|
||||
const matrix::Vector3f val_raw{(float)x, (float)y, (float)z}; |
||||
const matrix::Vector3f val_calibrated{ _rotation *(((val_raw * report.scaling) - _calibration_offset).emult(_calibration_scale))}; |
||||
|
||||
// Filtered values
|
||||
const matrix::Vector3f val_filtered{_filter.apply(val_calibrated)}; |
||||
|
||||
// Integrated values
|
||||
matrix::Vector3f integrated_value; |
||||
uint32_t integral_dt = 0; |
||||
|
||||
if (_integrator.put(timestamp, val_calibrated, integrated_value, integral_dt)) { |
||||
|
||||
// Raw values (ADC units 0 - 65535)
|
||||
report.x_raw = x; |
||||
report.y_raw = y; |
||||
report.z_raw = z; |
||||
|
||||
report.x = val_filtered(0); |
||||
report.y = val_filtered(1); |
||||
report.z = val_filtered(2); |
||||
|
||||
report.integral_dt = integral_dt; |
||||
report.x_integral = integrated_value(0); |
||||
report.y_integral = integrated_value(1); |
||||
report.z_integral = integrated_value(2); |
||||
|
||||
poll_notify(POLLIN); |
||||
_sensor_gyro_pub.update(); |
||||
} |
||||
} |
||||
|
||||
void PX4Gyroscope::print_status() |
||||
{ |
||||
PX4_INFO(GYRO_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); |
||||
PX4_INFO("sample rate: %d Hz", _sample_rate); |
||||
PX4_INFO("filter cutoff: %.3f Hz", (double)_filter.get_cutoff_freq()); |
||||
|
||||
PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1), |
||||
(double)_calibration_scale(2)); |
||||
PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1), |
||||
(double)_calibration_offset(2)); |
||||
|
||||
print_message(_sensor_gyro_pub.get()); |
||||
} |
@ -0,0 +1,88 @@
@@ -0,0 +1,88 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include <drivers/device/integrator.h> |
||||
#include <drivers/drv_gyro.h> |
||||
#include <drivers/drv_hrt.h> |
||||
#include <lib/cdev/CDev.hpp> |
||||
#include <lib/conversion/rotation.h> |
||||
#include <mathlib/math/filter/LowPassFilter2pVector3f.hpp> |
||||
#include <px4_module_params.h> |
||||
#include <uORB/uORB.h> |
||||
#include <uORB/Publication.hpp> |
||||
#include <uORB/topics/sensor_gyro.h> |
||||
|
||||
class PX4Gyroscope : public cdev::CDev, public ModuleParams |
||||
{ |
||||
|
||||
public: |
||||
PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation rotation); |
||||
~PX4Gyroscope() override; |
||||
|
||||
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override; |
||||
|
||||
void set_device_type(uint8_t devtype); |
||||
void set_error_count(uint64_t error_count) { _sensor_gyro_pub.get().error_count = error_count; } |
||||
void set_scale(float scale) { _sensor_gyro_pub.get().scaling = scale; } |
||||
void set_temperature(float temperature) { _sensor_gyro_pub.get().temperature = temperature; } |
||||
|
||||
void set_sample_rate(unsigned rate) { _sample_rate = rate; } |
||||
|
||||
void configure_filter(float cutoff_freq) { _filter.set_cutoff_frequency(_sample_rate, cutoff_freq); } |
||||
|
||||
void update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z); |
||||
|
||||
void print_status(); |
||||
|
||||
private: |
||||
|
||||
uORB::Publication<sensor_gyro_s> _sensor_gyro_pub; |
||||
|
||||
math::LowPassFilter2pVector3f _filter{1000, 100}; |
||||
Integrator _integrator{4000, true}; |
||||
|
||||
const matrix::Dcmf _rotation; |
||||
|
||||
matrix::Vector3f _calibration_scale{1.0f, 1.0f, 1.0f}; |
||||
matrix::Vector3f _calibration_offset{0.0f, 0.0f, 0.0f}; |
||||
|
||||
int _class_device_instance{-1}; |
||||
|
||||
unsigned _sample_rate{1000}; |
||||
|
||||
DEFINE_PARAMETERS( |
||||
(ParamFloat<px4::params::IMU_GYRO_CUTOFF>) _filter_cutoff |
||||
) |
||||
|
||||
}; |
@ -0,0 +1,34 @@
@@ -0,0 +1,34 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2018 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(drivers__magnetometer PX4Magnetometer.cpp) |
@ -0,0 +1,151 @@
@@ -0,0 +1,151 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include "PX4Magnetometer.hpp" |
||||
|
||||
PX4Magnetometer::PX4Magnetometer(const char *path, device::Device *interface, uint8_t dev_type, enum Rotation rotation, |
||||
float scale) : |
||||
CDev(path), |
||||
_interface(interface) |
||||
{ |
||||
_device_id.devid = _interface->get_device_id(); |
||||
// _device_id.devid_s.bus_type = (device::Device::DeviceBusType)_interface->get_device_bus_type();
|
||||
// _device_id.devid_s.bus = _interface->get_device_bus();
|
||||
// _device_id.devid_s.address = _interface->get_device_address();
|
||||
_device_id.devid_s.devtype = dev_type; |
||||
|
||||
CDev::init(); |
||||
|
||||
_class_device_instance = register_class_devname(MAG_BASE_DEVICE_PATH); |
||||
|
||||
_rotation = rotation; |
||||
_scale = scale; |
||||
|
||||
_cal.x_offset = 0; |
||||
_cal.x_scale = 1.0f; |
||||
_cal.y_offset = 0; |
||||
_cal.y_scale = 1.0f; |
||||
_cal.z_offset = 0; |
||||
_cal.z_scale = 1.0f; |
||||
} |
||||
|
||||
PX4Magnetometer::~PX4Magnetometer() |
||||
{ |
||||
if (_topic != nullptr) { |
||||
orb_unadvertise(_topic); |
||||
} |
||||
} |
||||
|
||||
int PX4Magnetometer::init() |
||||
{ |
||||
mag_report report{}; |
||||
report.device_id = _device_id.devid; |
||||
|
||||
if (_topic == nullptr) { |
||||
_topic = orb_advertise_multi(ORB_ID(sensor_mag), &report, &_orb_class_instance, ORB_PRIO_HIGH - 1); |
||||
|
||||
if (_topic == nullptr) { |
||||
PX4_ERR("Advertise failed."); |
||||
return PX4_ERROR; |
||||
} |
||||
} |
||||
|
||||
return PX4_OK; |
||||
} |
||||
|
||||
int PX4Magnetometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) |
||||
{ |
||||
switch (cmd) { |
||||
case MAGIOCSSCALE: |
||||
// Copy scale in.
|
||||
memcpy(&_cal, (struct mag_calibration_s *) arg, sizeof(_cal)); |
||||
return OK; |
||||
|
||||
case MAGIOCGSCALE: |
||||
// Copy scale out.
|
||||
memcpy((struct mag_calibration_s *) arg, &_cal, sizeof(_cal)); |
||||
return OK; |
||||
|
||||
case DEVIOCGDEVICEID: |
||||
return _device_id.devid; |
||||
|
||||
default: |
||||
// Give it to the superclass.
|
||||
return CDev::ioctl(filp, cmd, arg); |
||||
} |
||||
} |
||||
|
||||
void PX4Magnetometer::configure_filter(float sample_freq, float cutoff_freq) |
||||
{ |
||||
_filter_x.set_cutoff_frequency(sample_freq, cutoff_freq); |
||||
_filter_y.set_cutoff_frequency(sample_freq, cutoff_freq); |
||||
_filter_z.set_cutoff_frequency(sample_freq, cutoff_freq); |
||||
} |
||||
|
||||
// @TODO: use fixed point math to reclaim CPU usage
|
||||
int PX4Magnetometer::publish(float x, float y, float z, float temperature) |
||||
{ |
||||
sensor_mag_s report{}; |
||||
|
||||
report.device_id = _device_id.devid; |
||||
report.error_count = 0; |
||||
report.scaling = _scale; |
||||
report.timestamp = hrt_absolute_time(); |
||||
report.temperature = temperature; |
||||
report.is_external = false; |
||||
|
||||
|
||||
// Raw values (ADC units 0 - 65535)
|
||||
report.x_raw = x; |
||||
report.y_raw = y; |
||||
report.z_raw = z; |
||||
|
||||
// Apply the rotation.
|
||||
rotate_3f(_rotation, x, y, z); |
||||
|
||||
// Apply FS range scale and the calibrating offset/scale
|
||||
x = ((x * _scale) - _cal.x_offset) * _cal.x_scale; |
||||
y = ((y * _scale) - _cal.y_offset) * _cal.y_scale; |
||||
z = ((z * _scale) - _cal.z_offset) * _cal.z_scale; |
||||
|
||||
// Filtered values
|
||||
report.x = _filter_x.apply(x); |
||||
report.y = _filter_y.apply(y); |
||||
report.z = _filter_z.apply(z); |
||||
|
||||
poll_notify(POLLIN); |
||||
orb_publish(ORB_ID(sensor_mag), _topic, &report); |
||||
|
||||
return PX4_OK; |
||||
} |
@ -0,0 +1,81 @@
@@ -0,0 +1,81 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2018 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include <mathlib/math/filter/LowPassFilter2p.hpp> |
||||
|
||||
#include <drivers/device/integrator.h> |
||||
#include <drivers/drv_mag.h> |
||||
#include <drivers/drv_hrt.h> |
||||
#include <lib/drivers/device/Device.hpp> |
||||
#include <lib/cdev/CDev.hpp> |
||||
#include <lib/conversion/rotation.h> |
||||
#include <uORB/topics/sensor_mag.h> |
||||
#include <uORB/uORB.h> |
||||
|
||||
class PX4Magnetometer : public cdev::CDev |
||||
{ |
||||
|
||||
public: |
||||
PX4Magnetometer(const char *name, device::Device *interface, uint8_t dev_type, enum Rotation rotation, float scale); |
||||
~PX4Magnetometer() override; |
||||
|
||||
int init() override; |
||||
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override; |
||||
|
||||
int publish(float x, float y, float z, float temperature); |
||||
|
||||
void configure_filter(float sample_freq, float cutoff_freq); |
||||
|
||||
private: |
||||
// Pointer to the communication interface
|
||||
const device::Device *_interface{nullptr}; |
||||
|
||||
mag_calibration_s _cal{}; |
||||
|
||||
orb_advert_t _topic{nullptr}; |
||||
|
||||
device::Device::DeviceId _device_id{}; |
||||
|
||||
int _orb_class_instance{-1}; |
||||
|
||||
int _class_device_instance{-1}; |
||||
|
||||
enum Rotation _rotation {ROTATION_NONE}; |
||||
|
||||
float _scale{1.0f}; |
||||
|
||||
math::LowPassFilter2p _filter_x{100, 20}; |
||||
math::LowPassFilter2p _filter_y{100, 20}; |
||||
math::LowPassFilter2p _filter_z{100, 20}; |
||||
}; |
Loading…
Reference in new issue