mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 21:23:57 +08:00
Merge branch 'master' of github.com:PX4/Firmware into px4dev_new_param
This commit is contained in:
@@ -76,7 +76,7 @@ ORB_DECLARE(sensor_mag);
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#define _MAGIOCBASE (0x2300)
|
#define _MAGIOCBASE (0x2300)
|
||||||
#define _MAGIOC(_n) (_IOC(_MAGIOBASE, _n))
|
#define _MAGIOC(_n) (_IOC(_MAGIOCBASE, _n))
|
||||||
|
|
||||||
/** set the driver polling rate to (arg) Hz, or one of the MAG_POLLRATE constants */
|
/** set the driver polling rate to (arg) Hz, or one of the MAG_POLLRATE constants */
|
||||||
#define MAGIOCSPOLLRATE _MAGIOC(0)
|
#define MAGIOCSPOLLRATE _MAGIOC(0)
|
||||||
|
|||||||
@@ -0,0 +1,42 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (C) 2012 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
#
|
||||||
|
# HMC5883 driver
|
||||||
|
#
|
||||||
|
|
||||||
|
APPNAME = hmc5883
|
||||||
|
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
|
STACKSIZE = 2048
|
||||||
|
|
||||||
|
include $(APPDIR)/mk/app.mk
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -87,14 +87,25 @@ int attitude_estimator_bm_update(struct sensor_combined_s *raw, float_vect3 *eul
|
|||||||
gyro_values.z = raw->gyro_rad_s[2];
|
gyro_values.z = raw->gyro_rad_s[2];
|
||||||
|
|
||||||
float_vect3 accel_values;
|
float_vect3 accel_values;
|
||||||
accel_values.x = raw->accelerometer_m_s2[0] * 9.81f * 9.0f;
|
accel_values.x = (raw->accelerometer_m_s2[0] / 9.81f) * 100;
|
||||||
accel_values.y = raw->accelerometer_m_s2[1] * 9.81f * 9.0f;
|
accel_values.y = (raw->accelerometer_m_s2[1] / 9.81f) * 100;
|
||||||
accel_values.z = raw->accelerometer_m_s2[2] * 9.81f * 9.0f;
|
accel_values.z = (raw->accelerometer_m_s2[2] / 9.81f) * 100;
|
||||||
|
|
||||||
float_vect3 mag_values;
|
float_vect3 mag_values;
|
||||||
mag_values.x = raw->magnetometer_ga[0]*510.0f;
|
mag_values.x = raw->magnetometer_ga[0]*456.0f;
|
||||||
mag_values.y = raw->magnetometer_ga[1]*510.0f;
|
mag_values.y = raw->magnetometer_ga[1]*456.0f;
|
||||||
mag_values.z = raw->magnetometer_ga[2]*510.0f;
|
mag_values.z = raw->magnetometer_ga[2]*456.0f;
|
||||||
|
|
||||||
|
static int i = 0;
|
||||||
|
|
||||||
|
if (i == 500) {
|
||||||
|
printf("gyro: %8.4f\t%8.4f\t%8.4f\t accel: %8.4f\t%8.4f\t%8.4f\t mag: %8.4f\t%8.4f\t%8.4f\t\n",
|
||||||
|
gyro_values.x, gyro_values.y, gyro_values.z,
|
||||||
|
accel_values.x, accel_values.y, accel_values.z,
|
||||||
|
mag_values.x, mag_values.y, mag_values.z);
|
||||||
|
i = 0;
|
||||||
|
}
|
||||||
|
i++;
|
||||||
|
|
||||||
attitude_blackmagic(&accel_values, &mag_values, &gyro_values);
|
attitude_blackmagic(&accel_values, &mag_values, &gyro_values);
|
||||||
|
|
||||||
|
|||||||
@@ -86,6 +86,7 @@ CONFIGURED_APPS += attitude_estimator_ekf
|
|||||||
# Communication and Drivers
|
# Communication and Drivers
|
||||||
CONFIGURED_APPS += drivers/device
|
CONFIGURED_APPS += drivers/device
|
||||||
CONFIGURED_APPS += drivers/ms5611
|
CONFIGURED_APPS += drivers/ms5611
|
||||||
|
CONFIGURED_APPS += drivers/hmc5883
|
||||||
CONFIGURED_APPS += drivers/mpu6000
|
CONFIGURED_APPS += drivers/mpu6000
|
||||||
CONFIGURED_APPS += px4/px4io/driver
|
CONFIGURED_APPS += px4/px4io/driver
|
||||||
CONFIGURED_APPS += px4/fmu
|
CONFIGURED_APPS += px4/fmu
|
||||||
|
|||||||
Reference in New Issue
Block a user