aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/airspeed/airspeed.h6
-rw-r--r--src/drivers/ardrone_interface/ardrone_motor_control.h3
-rw-r--r--src/drivers/batt_smbus/batt_smbus.cpp30
-rw-r--r--src/drivers/boards/aerocore/aerocore_spi.c4
-rw-r--r--src/drivers/boards/aerocore/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v1/px4fmu_spi.c4
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/drivers/boards/px4io-v1/px4io_init.c2
-rw-r--r--src/drivers/boards/px4io-v2/board_config.h4
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_init.c2
-rw-r--r--src/drivers/device/i2c.h6
-rw-r--r--src/drivers/drv_airspeed.h2
-rw-r--r--src/drivers/drv_blinkm.h2
-rw-r--r--src/drivers/drv_hrt.h3
-rw-r--r--src/drivers/drv_mag.h1
-rw-r--r--src/drivers/drv_orb_dev.h2
-rw-r--r--src/drivers/drv_oreoled.h2
-rw-r--r--src/drivers/drv_pwm_input.h2
-rw-r--r--src/drivers/drv_pwm_output.h4
-rw-r--r--src/drivers/drv_rgbled.h4
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.c3
-rw-r--r--src/drivers/gimbal/gimbal.cpp83
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp23
-rw-r--r--src/drivers/hmc5883/hmc5883.h2
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp16
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp51
-rw-r--r--src/drivers/md25/BlockSysIdent.hpp3
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp156
-rw-r--r--src/drivers/ms5611/ms5611.h2
-rw-r--r--src/drivers/px4io/px4io.cpp18
31 files changed, 278 insertions, 168 deletions
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
index d6a88714b..cdaf244dd 100644
--- a/src/drivers/airspeed/airspeed.h
+++ b/src/drivers/airspeed/airspeed.h
@@ -90,7 +90,7 @@ static const int ERROR = -1;
class __EXPORT Airspeed : public device::I2C
{
public:
- Airspeed(int bus, int address, unsigned conversion_interval, const char* path);
+ Airspeed(int bus, int address, unsigned conversion_interval, const char *path);
virtual ~Airspeed();
virtual int init();
@@ -108,8 +108,8 @@ private:
perf_counter_t _buffer_overflows;
/* this class has pointer data members and should not be copied */
- Airspeed(const Airspeed&);
- Airspeed& operator=(const Airspeed&);
+ Airspeed(const Airspeed &);
+ Airspeed &operator=(const Airspeed &);
protected:
virtual int probe();
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.h b/src/drivers/ardrone_interface/ardrone_motor_control.h
index 78b603b63..dcc49a472 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.h
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.h
@@ -85,7 +85,8 @@ int ar_init_motors(int ardrone_uart, int gpio);
/**
* Set LED pattern.
*/
-void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green, uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
+void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green,
+ uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
/**
* Mix motors and output actuators
diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp
index a958fc60d..9f72bd56f 100644
--- a/src/drivers/batt_smbus/batt_smbus.cpp
+++ b/src/drivers/batt_smbus/batt_smbus.cpp
@@ -84,6 +84,7 @@
#define BATT_SMBUS_ADDR 0x0B ///< I2C address
#define BATT_SMBUS_TEMP 0x08 ///< temperature register
#define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
+#define BATT_SMBUS_REMAINING_CAPACITY 0x0f ///< predicted remaining battery capacity as a percentage
#define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
#define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
#define BATT_SMBUS_SERIALNUM 0x1c ///< serial number register
@@ -179,6 +180,7 @@ private:
orb_advert_t _batt_topic; ///< uORB battery topic
orb_id_t _batt_orb_id; ///< uORB battery topic ID
uint64_t _start_time; ///< system time we first attempt to communicate with battery
+ uint16_t _batt_design_capacity; ///< battery's design capacity in mAh (0 means unknown)
};
namespace
@@ -197,7 +199,8 @@ BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
_reports(nullptr),
_batt_topic(-1),
_batt_orb_id(nullptr),
- _start_time(0)
+ _start_time(0),
+ _batt_design_capacity(0)
{
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
@@ -263,7 +266,7 @@ BATT_SMBUS::test()
if (updated) {
if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
- warnx("V=%4.2f C=%4.2f", status.voltage_v, status.current_a);
+ warnx("V=%4.2f C=%4.2f DismAh=%4.2f", (float)status.voltage_v, (float)status.current_a, (float)status.discharged_mah);
}
}
@@ -279,6 +282,7 @@ BATT_SMBUS::search()
{
bool found_slave = false;
uint16_t tmp;
+ int16_t orig_addr = get_address();
// search through all valid SMBus addresses
for (uint8_t i = BATT_SMBUS_ADDR_MIN; i <= BATT_SMBUS_ADDR_MAX; i++) {
@@ -293,6 +297,9 @@ BATT_SMBUS::search()
usleep(1);
}
+ // restore original i2c address
+ set_address(orig_addr);
+
// display completion message
if (found_slave) {
warnx("Done.");
@@ -364,13 +371,28 @@ BATT_SMBUS::cycle()
new_report.voltage_v = ((float)tmp) / 1000.0f;
// read current
- usleep(1);
uint8_t buff[4];
if (read_block(BATT_SMBUS_CURRENT, buff, 4, false) == 4) {
new_report.current_a = -(float)((int32_t)((uint32_t)buff[3] << 24 | (uint32_t)buff[2] << 16 | (uint32_t)buff[1] << 8 | (uint32_t)buff[0])) / 1000.0f;
}
+ // read battery design capacity
+ if (_batt_design_capacity == 0) {
+ if (read_reg(BATT_SMBUS_DESIGN_CAPACITY, tmp) == OK) {
+ _batt_design_capacity = tmp;
+ }
+ }
+
+ // read remaining capacity
+ if (_batt_design_capacity > 0) {
+ if (read_reg(BATT_SMBUS_REMAINING_CAPACITY, tmp) == OK) {
+ if (tmp < _batt_design_capacity) {
+ new_report.discharged_mah = _batt_design_capacity - tmp;
+ }
+ }
+ }
+
// publish to orb
if (_batt_topic != -1) {
orb_publish(_batt_orb_id, _batt_topic, &new_report);
@@ -430,8 +452,6 @@ BATT_SMBUS::read_block(uint8_t reg, uint8_t *data, uint8_t max_len, bool append_
{
uint8_t buff[max_len + 2]; // buffer to hold results
- usleep(1);
-
// read bytes including PEC
int ret = transfer(&reg, 1, buff, max_len + 2);
diff --git a/src/drivers/boards/aerocore/aerocore_spi.c b/src/drivers/boards/aerocore/aerocore_spi.c
index e329bd9d1..0fa474a8c 100644
--- a/src/drivers/boards/aerocore/aerocore_spi.c
+++ b/src/drivers/boards/aerocore/aerocore_spi.c
@@ -136,8 +136,8 @@ __EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
switch (devid) {
case PX4_SPIDEV_GYRO:
- /* Making sure the other peripherals are not selected */
- stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
break;
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
index 776a2071e..19518d73d 100644
--- a/src/drivers/boards/aerocore/board_config.h
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -54,7 +54,7 @@ __BEGIN_DECLS
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
-
+
/****************************************************************************************************
* Definitions
****************************************************************************************************/
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 882ec6aa2..17fa9c542 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -52,7 +52,7 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include <stm32.h>
#include <arch/board/board.h>
-
+
/****************************************************************************************************
* Definitions
****************************************************************************************************/
diff --git a/src/drivers/boards/px4fmu-v1/px4fmu_spi.c b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
index 17e6862f7..16f94a9f2 100644
--- a/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v1/px4fmu_spi.c
@@ -90,8 +90,8 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
switch (devid) {
case PX4_SPIDEV_GYRO:
- /* Making sure the other peripherals are not selected */
- stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
break;
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 273af1023..6188e29ae 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -54,7 +54,7 @@ __BEGIN_DECLS
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
-
+
/****************************************************************************************************
* Definitions
****************************************************************************************************/
diff --git a/src/drivers/boards/px4io-v1/px4io_init.c b/src/drivers/boards/px4io-v1/px4io_init.c
index 8292da9e1..5a02a9716 100644
--- a/src/drivers/boards/px4io-v1/px4io_init.c
+++ b/src/drivers/boards/px4io-v1/px4io_init.c
@@ -87,7 +87,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_RELAY1_EN);
stm32_configgpio(GPIO_RELAY2_EN);
- /* turn off - all leds are active low */
+ /* turn off - all leds are active low */
stm32_gpiowrite(GPIO_LED1, true);
stm32_gpiowrite(GPIO_LED2, true);
stm32_gpiowrite(GPIO_LED3, true);
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
index 10a93be0b..99baee41d 100644
--- a/src/drivers/boards/px4io-v2/board_config.h
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -50,7 +50,7 @@
/* these headers are not C++ safe */
#include <stm32.h>
#include <arch/board/board.h>
-
+
/******************************************************************************
* Definitions
******************************************************************************/
@@ -117,7 +117,7 @@
#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
-/*
+/*
* High-resolution timer
*/
#define HRT_TIMER 1 /* use timer1 for the HRT */
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
index 5c3343ccc..fd7eb33c3 100644
--- a/src/drivers/boards/px4io-v2/px4iov2_init.c
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -126,7 +126,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
stm32_configgpio(GPIO_SBUS_OUTPUT);
-
+
/* sbus output enable is active low - disable it by default */
stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
stm32_configgpio(GPIO_SBUS_OENABLE);
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index 7bb4ae1af..cb13fed83 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -63,7 +63,7 @@ public:
static int set_bus_clock(unsigned bus, unsigned clock_hz);
static unsigned int _bus_clocks[3];
-
+
protected:
/**
* The number of times a read or write operation will be retried on
@@ -144,8 +144,8 @@ private:
uint32_t _frequency;
struct i2c_dev_s *_dev;
- I2C(const device::I2C&);
- I2C operator=(const device::I2C&);
+ I2C(const device::I2C &);
+ I2C operator=(const device::I2C &);
};
} // namespace device
diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h
index 2ff91d5d0..fddef3626 100644
--- a/src/drivers/drv_airspeed.h
+++ b/src/drivers/drv_airspeed.h
@@ -35,7 +35,7 @@
* @file drv_airspeed.h
*
* Airspeed driver interface.
- *
+ *
* @author Simon Wilks
*/
diff --git a/src/drivers/drv_blinkm.h b/src/drivers/drv_blinkm.h
index 7258c9e84..8568436d3 100644
--- a/src/drivers/drv_blinkm.h
+++ b/src/drivers/drv_blinkm.h
@@ -60,7 +60,7 @@
/** play the numbered script in (arg), repeating forever */
#define BLINKM_PLAY_SCRIPT _BLINKMIOC(2)
-/**
+/**
* Set the user script; (arg) is a pointer to an array of script lines,
* where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
*
diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h
index 8bfc90c64..a40943d3f 100644
--- a/src/drivers/drv_hrt.h
+++ b/src/drivers/drv_hrt.h
@@ -127,7 +127,8 @@ __EXPORT extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, h
* Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
* jitter but should not drift.
*/
-__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg);
+__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval,
+ hrt_callout callout, void *arg);
/*
* If this returns true, the entry has been invoked and removed from the callout list,
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 7fcff9d38..ca33966b0 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -63,6 +63,7 @@ struct mag_report {
float z;
float range_ga;
float scaling;
+ float temperature;
int16_t x_raw;
int16_t y_raw;
diff --git a/src/drivers/drv_orb_dev.h b/src/drivers/drv_orb_dev.h
index e0b16fa5c..c1db6b534 100644
--- a/src/drivers/drv_orb_dev.h
+++ b/src/drivers/drv_orb_dev.h
@@ -36,7 +36,7 @@
/**
* @file drv_orb_dev.h
- *
+ *
* uORB published object driver.
*/
diff --git a/src/drivers/drv_oreoled.h b/src/drivers/drv_oreoled.h
index 0dcb10a7b..00e368318 100644
--- a/src/drivers/drv_oreoled.h
+++ b/src/drivers/drv_oreoled.h
@@ -117,7 +117,7 @@ enum oreoled_macro {
OREOLED_PARAM_MACRO_ENUM_COUNT
};
-/*
+/*
structure passed to OREOLED_SET_RGB ioctl()
Note that the driver scales the brightness to 0 to 255, regardless
of the hardware scaling
diff --git a/src/drivers/drv_pwm_input.h b/src/drivers/drv_pwm_input.h
index 778d9fcf5..47b84e6e1 100644
--- a/src/drivers/drv_pwm_input.h
+++ b/src/drivers/drv_pwm_input.h
@@ -46,6 +46,6 @@ __BEGIN_DECLS
/*
* Initialise the timer
*/
-__EXPORT extern int pwm_input_main(int argc, char * argv[]);
+__EXPORT extern int pwm_input_main(int argc, char *argv[]);
__END_DECLS
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 35e9619f0..6271ad208 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -78,7 +78,7 @@ __BEGIN_DECLS
/**
* Highest PWM allowed as the minimum PWM
*/
-#define PWM_HIGHEST_MIN 1300
+#define PWM_HIGHEST_MIN 1600
/**
* Highest maximum PWM in us
@@ -93,7 +93,7 @@ __BEGIN_DECLS
/**
* Lowest PWM allowed as the maximum PWM
*/
-#define PWM_LOWEST_MAX 1700
+#define PWM_LOWEST_MAX 1400
/**
* Do not output a channel with this value
diff --git a/src/drivers/drv_rgbled.h b/src/drivers/drv_rgbled.h
index b10caf56a..063376868 100644
--- a/src/drivers/drv_rgbled.h
+++ b/src/drivers/drv_rgbled.h
@@ -58,7 +58,7 @@
/** play the numbered script in (arg), repeating forever */
#define RGBLED_PLAY_SCRIPT _RGBLEDIOC(2)
-/**
+/**
* Set the user script; (arg) is a pointer to an array of script lines,
* where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
*
@@ -79,7 +79,7 @@
#define RGBLED_SET_PATTERN _RGBLEDIOC(7)
-/*
+/*
structure passed to RGBLED_SET_RGB ioctl()
Note that the driver scales the brightness to 0 to 255, regardless
of the hardware scaling
diff --git a/src/drivers/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
index 890fada16..de22a888d 100644
--- a/src/drivers/frsky_telemetry/frsky_data.c
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -222,6 +222,7 @@ void frsky_send_frame2(int uart)
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
char lat_ns = 0, lon_ew = 0;
int sec = 0;
+
if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
struct tm *tm_gps = gmtime(&time_gps);
@@ -232,7 +233,7 @@ void frsky_send_frame2(int uart)
lon = frsky_format_gps(fabsf(global_pos.lon));
lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e)
- * 25.0f / 46.0f;
+ * 25.0f / 46.0f;
alt = global_pos.alt;
sec = tm_gps->tm_sec;
}
diff --git a/src/drivers/gimbal/gimbal.cpp b/src/drivers/gimbal/gimbal.cpp
index ccda4c0a5..1e27309d8 100644
--- a/src/drivers/gimbal/gimbal.cpp
+++ b/src/drivers/gimbal/gimbal.cpp
@@ -121,8 +121,12 @@ private:
int _vehicle_command_sub;
int _att_sub;
- bool _attitude_compensation;
+ bool _attitude_compensation_roll;
+ bool _attitude_compensation_pitch;
+ bool _attitude_compensation_yaw;
bool _initialized;
+ bool _control_cmd_set;
+ bool _config_cmd_set;
orb_advert_t _actuator_controls_2_topic;
@@ -130,6 +134,9 @@ private:
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
+ struct vehicle_command_s _control_cmd;
+ struct vehicle_command_s _config_cmd;
+
/**
* Initialise the automatic measurement state machine and start it.
*
@@ -169,7 +176,9 @@ Gimbal::Gimbal() :
CDev("Gimbal", GIMBAL_DEVICE_PATH),
_vehicle_command_sub(-1),
_att_sub(-1),
- _attitude_compensation(true),
+ _attitude_compensation_roll(true),
+ _attitude_compensation_pitch(true),
+ _attitude_compensation_yaw(true),
_initialized(false),
_actuator_controls_2_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "gimbal_read")),
@@ -221,7 +230,9 @@ Gimbal::ioctl(struct file *filp, int cmd, unsigned long arg)
switch (cmd) {
case GIMBALIOCATTCOMPENSATE:
- _attitude_compensation = (arg != 0);
+ _attitude_compensation_roll = (arg != 0);
+ _attitude_compensation_pitch = (arg != 0);
+ _attitude_compensation_yaw = (arg != 0);
return OK;
default:
@@ -286,22 +297,30 @@ Gimbal::cycle()
float yaw = 0.0f;
- if (_attitude_compensation) {
- if (_att_sub < 0) {
- _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- }
+ if (_att_sub < 0) {
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ }
- vehicle_attitude_s att;
+ vehicle_attitude_s att;
- orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att);
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att);
+ if (_attitude_compensation_roll) {
roll = -att.roll;
+ updated = true;
+ }
+
+ if (_attitude_compensation_pitch) {
pitch = -att.pitch;
- yaw = att.yaw;
+ updated = true;
+ }
+ if (_attitude_compensation_yaw) {
+ yaw = att.yaw;
updated = true;
}
+
struct vehicle_command_s cmd;
bool cmd_updated;
@@ -312,22 +331,47 @@ Gimbal::cycle()
orb_copy(ORB_ID(vehicle_command), _vehicle_command_sub, &cmd);
- VEHICLE_MOUNT_MODE mountMode = (VEHICLE_MOUNT_MODE)cmd.param7;
- debug("cmd: %d, mountMode %d | param1: %8.4f param2: %8.4f", cmd.command, mountMode, (double)cmd.param1, (double)cmd.param2);
+ if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL
+ || cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT) {
+
+ _control_cmd = cmd;
+ _control_cmd_set = true;
+
+ } else if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONFIGURE) {
- if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
+ _config_cmd = cmd;
+ _config_cmd_set = true;
+ }
+
+ }
+
+ if (_config_cmd_set) {
+
+ _config_cmd_set = false;
+
+ _attitude_compensation_roll = (int)_config_cmd.param2 == 1;
+ _attitude_compensation_pitch = (int)_config_cmd.param3 == 1;
+ _attitude_compensation_yaw = (int)_config_cmd.param4 == 1;
+
+ }
+
+ if (_control_cmd_set) {
+
+ VEHICLE_MOUNT_MODE mountMode = (VEHICLE_MOUNT_MODE)_control_cmd.param7;
+ debug("control_cmd: %d, mountMode %d | param1: %8.4f param2: %8.4f", _control_cmd.command, mountMode, (double)_control_cmd.param1, (double)_control_cmd.param2);
+
+ if (_control_cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
/* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
- roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;
- pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param2;
- yaw += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param3;
+ roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param1;
+ pitch += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param2;
+ yaw += 1.0f / M_PI_F * M_DEG_TO_RAD_F * _control_cmd.param3;
updated = true;
-
}
- if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
- float gimbalDirectionQuat[] = {cmd.param1, cmd.param2, cmd.param3, cmd.param4};
+ if (_control_cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && mountMode == VEHICLE_MOUNT_MODE_MAVLINK_TARGETING) {
+ float gimbalDirectionQuat[] = {_control_cmd.param1, _control_cmd.param2, _control_cmd.param3, _control_cmd.param4};
math::Vector<3> gimablDirectionEuler = math::Quaternion(gimbalDirectionQuat).to_dcm().to_euler();
roll += gimablDirectionEuler(0);
@@ -336,6 +380,7 @@ Gimbal::cycle()
updated = true;
}
+
}
if (updated) {
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 7560ef20b..fd4d4cff5 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -848,6 +848,10 @@ HMC5883::collect()
struct mag_report new_report;
bool sensor_is_onboard = false;
+ float xraw_f;
+ float yraw_f;
+ float zraw_f;
+
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
new_report.timestamp = hrt_absolute_time();
new_report.error_count = perf_event_count(_comms_errors);
@@ -907,17 +911,24 @@ HMC5883::collect()
report.x = -report.x;
}
- /* the standard external mag by 3DR has x pointing to the
+ /* the standard external mag by 3DR has x pointing to the
* right, y pointing backwards, and z down, therefore switch x
* and y and invert y */
- new_report.x = ((-report.y * _range_scale) - _scale.x_offset) * _scale.x_scale;
+ xraw_f = -report.y;
+ yraw_f = report.x;
+ zraw_f = report.z;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ new_report.x = ((xraw_f * _range_scale) - _scale.x_offset) * _scale.x_scale;
/* flip axes and negate value for y */
- new_report.y = ((report.x * _range_scale) - _scale.y_offset) * _scale.y_scale;
+ new_report.y = ((yraw_f * _range_scale) - _scale.y_offset) * _scale.y_scale;
/* z remains z */
- new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale;
+ new_report.z = ((zraw_f * _range_scale) - _scale.z_offset) * _scale.z_scale;
- // apply user specified rotation
- rotate_3f(_rotation, new_report.x, new_report.y, new_report.z);
+ /* this sensor does not measure temperature, output a constant value */
+ new_report.temperature = 0.0f;
if (!(_pub_blocked)) {
diff --git a/src/drivers/hmc5883/hmc5883.h b/src/drivers/hmc5883/hmc5883.h
index e91e91fc0..9607fe614 100644
--- a/src/drivers/hmc5883/hmc5883.h
+++ b/src/drivers/hmc5883/hmc5883.h
@@ -50,4 +50,4 @@
/* interface factories */
extern device::Device *HMC5883_SPI_interface(int bus) weak_function;
extern device::Device *HMC5883_I2C_interface(int bus) weak_function;
-typedef device::Device* (*HMC5883_constructor)(int);
+typedef device::Device *(*HMC5883_constructor)(int);
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 4c41491a8..768723640 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -1029,9 +1029,16 @@ L3GD20::measure()
report.temperature_raw = raw_report.temp;
- report.x = ((report.x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
- report.y = ((report.y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
- report.z = ((report.z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
+ float xraw_f = report.x_raw;
+ float yraw_f = report.y_raw;
+ float zraw_f = report.z_raw;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ report.x = ((xraw_f * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
+ report.y = ((yraw_f * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
+ report.z = ((zraw_f * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
report.x = _gyro_filter_x.apply(report.x);
report.y = _gyro_filter_y.apply(report.y);
@@ -1039,9 +1046,6 @@ L3GD20::measure()
report.temperature = L3GD20_TEMP_OFFSET_CELSIUS - raw_report.temp;
- // apply user specified rotation
- rotate_3f(_rotation, report.x, report.y, report.z);
-
report.scaling = _gyro_range_scale;
report.range_rad_s = _gyro_range_rad_s;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index b5f01b942..e594c92a1 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -305,6 +305,9 @@ private:
float _last_accel[3];
uint8_t _constant_accel_count;
+ // last temperature value
+ float _last_temperature;
+
// this is used to support runtime checking of key
// configuration registers to detect SPI bus errors and sensor
// reset
@@ -567,6 +570,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota
_accel_filter_z(LSM303D_ACCEL_DEFAULT_RATE, LSM303D_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
_rotation(rotation),
_constant_accel_count(0),
+ _last_temperature(0),
_checked_next(0)
{
@@ -711,7 +715,7 @@ LSM303D::reset()
/* enable mag */
write_checked_reg(ADDR_CTRL_REG7, REG7_CONT_MODE_M);
- write_checked_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M);
+ write_checked_reg(ADDR_CTRL_REG5, REG5_RES_HIGH_M | REG5_ENABLE_T);
write_checked_reg(ADDR_CTRL_REG3, 0x04); // DRDY on ACCEL on INT1
write_checked_reg(ADDR_CTRL_REG4, 0x04); // DRDY on MAG on INT2
@@ -1507,6 +1511,9 @@ LSM303D::measure()
accel_report.timestamp = hrt_absolute_time();
+ // use the temperature from the last mag reading
+ accel_report.temperature = _last_temperature;
+
// report the error count as the sum of the number of bad
// register reads and bad values. This allows the higher level
// code to decide if it should use this sensor based on
@@ -1517,9 +1524,16 @@ LSM303D::measure()
accel_report.y_raw = raw_accel_report.y;
accel_report.z_raw = raw_accel_report.z;
- float x_in_new = ((accel_report.x_raw * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- float y_in_new = ((accel_report.y_raw * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- float z_in_new = ((accel_report.z_raw * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+ float xraw_f = raw_accel_report.x;
+ float yraw_f = raw_accel_report.y;
+ float zraw_f = raw_accel_report.z;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ float x_in_new = ((xraw_f * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((yraw_f * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((zraw_f * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
/*
we have logs where the accelerometers get stuck at a fixed
@@ -1555,9 +1569,6 @@ LSM303D::measure()
accel_report.y = _accel_filter_y.apply(y_in_new);
accel_report.z = _accel_filter_z.apply(z_in_new);
- // apply user specified rotation
- rotate_3f(_rotation, accel_report.x, accel_report.y, accel_report.z);
-
accel_report.scaling = _accel_range_scale;
accel_report.range_m_s2 = _accel_range_m_s2;
@@ -1584,6 +1595,7 @@ LSM303D::mag_measure()
#pragma pack(push, 1)
struct {
uint8_t cmd;
+ int16_t temperature;
uint8_t status;
int16_t x;
int16_t y;
@@ -1599,7 +1611,7 @@ LSM303D::mag_measure()
/* fetch data from the sensor */
memset(&raw_mag_report, 0, sizeof(raw_mag_report));
- raw_mag_report.cmd = ADDR_STATUS_M | DIR_READ | ADDR_INCREMENT;
+ raw_mag_report.cmd = ADDR_OUT_TEMP_L | DIR_READ | ADDR_INCREMENT;
transfer((uint8_t *)&raw_mag_report, (uint8_t *)&raw_mag_report, sizeof(raw_mag_report));
/*
@@ -1623,19 +1635,29 @@ LSM303D::mag_measure()
mag_report.x_raw = raw_mag_report.x;
mag_report.y_raw = raw_mag_report.y;
mag_report.z_raw = raw_mag_report.z;
- mag_report.x = ((mag_report.x_raw * _mag_range_scale) - _mag_scale.x_offset) * _mag_scale.x_scale;
- mag_report.y = ((mag_report.y_raw * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
- mag_report.z = ((mag_report.z_raw * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
+
+ float xraw_f = mag_report.x_raw;
+ float yraw_f = mag_report.y_raw;
+ float zraw_f = mag_report.z_raw;
+
+ /* apply user specified rotation */
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ mag_report.x = ((xraw_f * _mag_range_scale) - _mag_scale.x_offset) * _mag_scale.x_scale;
+ mag_report.y = ((yraw_f * _mag_range_scale) - _mag_scale.y_offset) * _mag_scale.y_scale;
+ mag_report.z = ((zraw_f * _mag_range_scale) - _mag_scale.z_offset) * _mag_scale.z_scale;
mag_report.scaling = _mag_range_scale;
mag_report.range_ga = (float)_mag_range_ga;
mag_report.error_count = perf_event_count(_bad_registers) + perf_event_count(_bad_values);
- // apply user specified rotation
- rotate_3f(_rotation, mag_report.x, mag_report.y, mag_report.z);
+ /* remember the temperature. The datasheet isn't clear, but it
+ * seems to be a signed offset from 25 degrees C in units of 0.125C
+ */
+ _last_temperature = 25 + (raw_mag_report.temperature * 0.125f);
+ mag_report.temperature = _last_temperature;
_mag_reports->force(&mag_report);
- /* XXX please check this poll_notify, is it the right one? */
/* notify anyone waiting for data */
poll_notify(POLLIN);
@@ -1672,6 +1694,7 @@ LSM303D::print_info()
(unsigned)_checked_values[i]);
}
}
+ ::printf("temperature: %.2f\n", (double)_last_temperature);
}
void
diff --git a/src/drivers/md25/BlockSysIdent.hpp b/src/drivers/md25/BlockSysIdent.hpp
index 270635f40..e8dd4ee9c 100644
--- a/src/drivers/md25/BlockSysIdent.hpp
+++ b/src/drivers/md25/BlockSysIdent.hpp
@@ -1,7 +1,8 @@
#include <controllib/block/Block.hpp>
#include <controllib/block/BlockParam.hpp>
-class BlockSysIdent : public control::Block {
+class BlockSysIdent : public control::Block
+{
public:
BlockSysIdent();
private:
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index b48ea8577..b6642e2bb 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -284,6 +284,9 @@ private:
// self test
volatile bool _in_factory_test;
+ // last temperature reading for print_info()
+ float _last_temperature;
+
/**
* Start automatic measurement.
*/
@@ -359,7 +362,7 @@ private:
* @param max_g The maximum G value the range must support.
* @return OK if the value can be supported, -ERANGE otherwise.
*/
- int set_range(unsigned max_g);
+ int set_accel_range(unsigned max_g);
/**
* Swap a 16-bit value read from the MPU6000 to native byte order.
@@ -518,7 +521,8 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev
_gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ),
_rotation(rotation),
_checked_next(0),
- _in_factory_test(false)
+ _in_factory_test(false),
+ _last_temperature(0)
{
// disable debug() calls
_debug_enabled = false;
@@ -713,37 +717,7 @@ int MPU6000::reset()
_gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F);
_gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F;
- // product-specific scaling
- switch (_product) {
- case MPU6000ES_REV_C4:
- case MPU6000ES_REV_C5:
- case MPU6000_REV_C4:
- case MPU6000_REV_C5:
- // Accel scale 8g (4096 LSB/g)
- // Rev C has different scaling than rev D
- write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
- break;
-
- case MPU6000ES_REV_D6:
- case MPU6000ES_REV_D7:
- case MPU6000ES_REV_D8:
- case MPU6000_REV_D6:
- case MPU6000_REV_D7:
- case MPU6000_REV_D8:
- case MPU6000_REV_D9:
- case MPU6000_REV_D10:
- // default case to cope with new chip revisions, which
- // presumably won't have the accel scaling bug
- default:
- // Accel scale 8g (4096 LSB/g)
- write_checked_reg(MPUREG_ACCEL_CONFIG, 2 << 3);
- break;
- }
-
- // Correct accel scale factors of 4096 LSB/g
- // scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
- _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
+ set_accel_range(8);
usleep(1000);
@@ -1297,11 +1271,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return OK;
case ACCELIOCSRANGE:
- /* XXX not implemented */
- // XXX change these two values on set:
- // _accel_range_scale = (9.81f / 4096.0f);
- // _accel_range_m_s2 = 8.0f * 9.81f;
- return -EINVAL;
+ return set_accel_range(arg);
+
case ACCELIOCGRANGE:
return (unsigned long)((_accel_range_m_s2)/MPU6000_ONE_G + 0.5f);
@@ -1451,44 +1422,46 @@ MPU6000::write_checked_reg(unsigned reg, uint8_t value)
}
int
-MPU6000::set_range(unsigned max_g)
+MPU6000::set_accel_range(unsigned max_g_in)
{
-#if 0
- uint8_t rangebits;
- float rangescale;
-
- if (max_g > 16) {
- return -ERANGE;
-
- } else if (max_g > 8) { /* 16G */
- rangebits = OFFSET_LSB1_RANGE_16G;
- rangescale = 1.98;
-
- } else if (max_g > 4) { /* 8G */
- rangebits = OFFSET_LSB1_RANGE_8G;
- rangescale = 0.99;
-
- } else if (max_g > 3) { /* 4G */
- rangebits = OFFSET_LSB1_RANGE_4G;
- rangescale = 0.5;
-
- } else if (max_g > 2) { /* 3G */
- rangebits = OFFSET_LSB1_RANGE_3G;
- rangescale = 0.38;
-
- } else if (max_g > 1) { /* 2G */
- rangebits = OFFSET_LSB1_RANGE_2G;
- rangescale = 0.25;
+ // workaround for bugged versions of MPU6k (rev C)
+ switch (_product) {
+ case MPU6000ES_REV_C4:
+ case MPU6000ES_REV_C5:
+ case MPU6000_REV_C4:
+ case MPU6000_REV_C5:
+ write_checked_reg(MPUREG_ACCEL_CONFIG, 1 << 3);
+ _accel_range_scale = (MPU6000_ONE_G / 4096.0f);
+ _accel_range_m_s2 = 8.0f * MPU6000_ONE_G;
+ return OK;
+ }
- } else { /* 1G */
- rangebits = OFFSET_LSB1_RANGE_1G;
- rangescale = 0.13;
+ uint8_t afs_sel;
+ float lsb_per_g;
+ float max_accel_g;
+
+ if (max_g_in > 8) { // 16g - AFS_SEL = 3
+ afs_sel = 3;
+ lsb_per_g = 2048;
+ max_accel_g = 16;
+ } else if (max_g_in > 4) { // 8g - AFS_SEL = 2
+ afs_sel = 2;
+ lsb_per_g = 4096;
+ max_accel_g = 8;
+ } else if (max_g_in > 2) { // 4g - AFS_SEL = 1
+ afs_sel = 1;
+ lsb_per_g = 8192;
+ max_accel_g = 4;
+ } else { // 2g - AFS_SEL = 0
+ afs_sel = 0;
+ lsb_per_g = 16384;
+ max_accel_g = 2;
}
- /* adjust sensor configuration */
- modify_reg(ADDR_OFFSET_LSB1, OFFSET_LSB1_RANGE_MASK, rangebits);
- _range_scale = rangescale;
-#endif
+ write_checked_reg(MPUREG_ACCEL_CONFIG, afs_sel << 3);
+ _accel_range_scale = (MPU6000_ONE_G / lsb_per_g);
+ _accel_range_m_s2 = max_accel_g * MPU6000_ONE_G;
+
return OK;
}
@@ -1711,43 +1684,53 @@ MPU6000::measure()
arb.y_raw = report.accel_y;
arb.z_raw = report.accel_z;
- float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+ float xraw_f = report.accel_x;
+ float yraw_f = report.accel_y;
+ float zraw_f = report.accel_z;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ float x_in_new = ((xraw_f * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((yraw_f * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((zraw_f * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
arb.x = _accel_filter_x.apply(x_in_new);
arb.y = _accel_filter_y.apply(y_in_new);
arb.z = _accel_filter_z.apply(z_in_new);
- // apply user specified rotation
- rotate_3f(_rotation, arb.x, arb.y, arb.z);
-
arb.scaling = _accel_range_scale;
arb.range_m_s2 = _accel_range_m_s2;
+ _last_temperature = (report.temp) / 361.0f + 35.0f;
+
arb.temperature_raw = report.temp;
- arb.temperature = (report.temp) / 361.0f + 35.0f;
+ arb.temperature = _last_temperature;
grb.x_raw = report.gyro_x;
grb.y_raw = report.gyro_y;
grb.z_raw = report.gyro_z;
- float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
- float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
- float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
+ xraw_f = report.gyro_x;
+ yraw_f = report.gyro_y;
+ zraw_f = report.gyro_z;
+
+ // apply user specified rotation
+ rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
+
+ float x_gyro_in_new = ((xraw_f * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
+ float y_gyro_in_new = ((yraw_f * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
+ float z_gyro_in_new = ((zraw_f * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
grb.x = _gyro_filter_x.apply(x_gyro_in_new);
grb.y = _gyro_filter_y.apply(y_gyro_in_new);
grb.z = _gyro_filter_z.apply(z_gyro_in_new);
- // apply user specified rotation
- rotate_3f(_rotation, grb.x, grb.y, grb.z);
-
grb.scaling = _gyro_range_scale;
grb.range_rad_s = _gyro_range_rad_s;
grb.temperature_raw = report.temp;
- grb.temperature = (report.temp) / 361.0f + 35.0f;
+ grb.temperature = _last_temperature;
_accel_reports->force(&arb);
_gyro_reports->force(&grb);
@@ -1795,6 +1778,7 @@ MPU6000::print_info()
(unsigned)_checked_values[i]);
}
}
+ ::printf("temperature: %.1f\n", (double)_last_temperature);
}
void
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
index c8211b8dd..c946e38cb 100644
--- a/src/drivers/ms5611/ms5611.h
+++ b/src/drivers/ms5611/ms5611.h
@@ -82,4 +82,4 @@ extern bool crc4(uint16_t *n_prom);
/* interface factories */
extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum) weak_function;
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint8_t busnum) weak_function;
-typedef device::Device* (*MS5611_constructor)(ms5611::prom_u &prom_buf, uint8_t busnum);
+typedef device::Device *(*MS5611_constructor)(ms5611::prom_u &prom_buf, uint8_t busnum);
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 1c4cc1838..3bd2c06a4 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1291,6 +1291,24 @@ PX4IO::io_set_rc_config()
input_map[ichan - 1] = 4;
}
+ /* AUX 1*/
+ param_get(param_find("RC_MAP_AUX1"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 5;
+ }
+
+ /* AUX 2*/
+ param_get(param_find("RC_MAP_AUX2"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 6;
+ }
+
+ /* AUX 3*/
+ param_get(param_find("RC_MAP_AUX3"), &ichan);
+ if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {
+ input_map[ichan - 1] = 7;
+ }
+
/* MAIN MODE SWITCH */
param_get(param_find("RC_MAP_MODE_SW"), &ichan);
if ((ichan > 0) && (ichan <= (int)_max_rc_input)) {