forked from Archive/PX4-Autopilot
Merge branch 'master' of https://github.com/PX4/Firmware into archlinux
This commit is contained in:
commit
8e45ddc42b
|
@ -0,0 +1,164 @@
|
|||
#
|
||||
# Assorted ARMv7M macros
|
||||
#
|
||||
|
||||
echo Loading ARMv7M GDB macros. Use 'help armv7m' for more information.\n
|
||||
|
||||
define armv7m
|
||||
echo Use 'help armv7m' for more information.\n
|
||||
end
|
||||
|
||||
document armv7m
|
||||
. Various macros for working with the ARMv7M family of processors.
|
||||
.
|
||||
. vecstate
|
||||
. Print information about the current exception handling state.
|
||||
.
|
||||
. Use 'help <macro>' for more specific help.
|
||||
end
|
||||
|
||||
|
||||
define vecstate
|
||||
set $icsr = *(unsigned *)0xe000ed04
|
||||
set $vect = $icsr & 0x1ff
|
||||
set $pend = ($icsr & 0x1ff000) >> 12
|
||||
set $shcsr = *(unsigned *)0xe000ed24
|
||||
set $cfsr = *(unsigned *)0xe000ed28
|
||||
set $mmfsr = $cfsr & 0xff
|
||||
set $bfsr = ($cfsr >> 8) & 0xff
|
||||
set $ufsr = ($cfsr >> 16) & 0xffff
|
||||
set $hfsr = *(unsigned *)0xe000ed2c
|
||||
set $bfar = *(unsigned *)0xe000ed38
|
||||
set $mmfar = *(unsigned *)0xe000ed34
|
||||
|
||||
if $vect < 15
|
||||
|
||||
if $hfsr != 0
|
||||
printf "HardFault:"
|
||||
if $hfsr & (1<<1)
|
||||
printf " due to vector table read fault\n"
|
||||
end
|
||||
if $hfsr & (1<<30)
|
||||
printf " forced due to escalated or disabled configurable fault (see below)\n"
|
||||
end
|
||||
if $hfsr & (1<<31)
|
||||
printf " due to an unexpected debug event\n"
|
||||
end
|
||||
end
|
||||
if $mmfsr != 0
|
||||
printf "MemManage:"
|
||||
if $mmfsr & (1<<5)
|
||||
printf " during lazy FP state save"
|
||||
end
|
||||
if $mmfsr & (1<<4)
|
||||
printf " during exception entry"
|
||||
end
|
||||
if $mmfsr & (1<<3)
|
||||
printf " during exception return"
|
||||
end
|
||||
if $mmfsr & (1<<0)
|
||||
printf " during data access"
|
||||
end
|
||||
if $mmfsr & (1<<0)
|
||||
printf " during instruction prefetch"
|
||||
end
|
||||
if $mmfsr & (1<<7)
|
||||
printf " accessing 0x%08x", $mmfar
|
||||
end
|
||||
printf "\n"
|
||||
end
|
||||
if $bfsr != 0
|
||||
printf "BusFault:"
|
||||
if $bfsr & (1<<2)
|
||||
printf " (imprecise)"
|
||||
end
|
||||
if $bfsr & (1<<1)
|
||||
printf " (precise)"
|
||||
end
|
||||
if $bfsr & (1<<5)
|
||||
printf " during lazy FP state save"
|
||||
end
|
||||
if $bfsr & (1<<4)
|
||||
printf " during exception entry"
|
||||
end
|
||||
if $bfsr & (1<<3)
|
||||
printf " during exception return"
|
||||
end
|
||||
if $bfsr & (1<<0)
|
||||
printf " during instruction prefetch"
|
||||
end
|
||||
if $bfsr & (1<<7)
|
||||
printf " accessing 0x%08x", $bfar
|
||||
end
|
||||
printf "\n"
|
||||
end
|
||||
if $ufsr != 0
|
||||
printf "UsageFault"
|
||||
if $ufsr & (1<<9)
|
||||
printf " due to divide-by-zero"
|
||||
end
|
||||
if $ufsr & (1<<8)
|
||||
printf " due to unaligned memory access"
|
||||
end
|
||||
if $ufsr & (1<<3)
|
||||
printf " due to access to disabled/absent coprocessor"
|
||||
end
|
||||
if $ufsr & (1<<2)
|
||||
printf " due to a bad EXC_RETURN value"
|
||||
end
|
||||
if $ufsr & (1<<1)
|
||||
printf " due to bad T or IT bits in EPSR"
|
||||
end
|
||||
if $ufsr & (1<<0)
|
||||
printf " due to executing an undefined instruction"
|
||||
end
|
||||
printf "\n"
|
||||
end
|
||||
else
|
||||
if $vect >= 15
|
||||
printf "Handling vector %u\n", $vect
|
||||
end
|
||||
end
|
||||
if ((unsigned)$lr & 0xf0000000) == 0xf0000000
|
||||
if ($lr & 1)
|
||||
printf "exception frame is on MSP\n"
|
||||
#set $frame_ptr = (unsigned *)$msp
|
||||
set $frame_ptr = (unsigned *)$sp
|
||||
else
|
||||
printf "exception frame is on PSP, backtrace may not be possible\n"
|
||||
#set $frame_ptr = (unsigned *)$psp
|
||||
set $frame_ptr = (unsigned *)$sp
|
||||
end
|
||||
if $lr & 0x10
|
||||
set $fault_sp = $frame_ptr + (8 * 4)
|
||||
else
|
||||
set $fault_sp = $frame_ptr + (26 * 4)
|
||||
end
|
||||
|
||||
|
||||
printf " r0: %08x r1: %08x r2: %08x r3: %08x\n", $frame_ptr[0], $frame_ptr[1], $frame_ptr[2], $frame_ptr[3]
|
||||
printf " r4: %08x r5: %08x r6: %08x r7: %08x\n", $r4, $r5, $r6, $r7
|
||||
printf " r8: %08x r9: %08x r10: %08x r11: %08x\n", $r8, $r9, $r10, $r11
|
||||
printf " r12: %08x\n", $frame_ptr[4]
|
||||
printf " sp: %08x lr: %08x pc: %08x PSR: %08x\n", $fault_sp, $frame_ptr[5], $frame_ptr[6], $frame_ptr[7]
|
||||
|
||||
# Swap to the context of the faulting code and try to print a backtrace
|
||||
set $saved_sp = $sp
|
||||
set $sp = $fault_sp
|
||||
set $saved_lr = $lr
|
||||
set $lr = $frame_ptr[5]
|
||||
set $saved_pc = $pc
|
||||
set $pc = $frame_ptr[6]
|
||||
bt
|
||||
set $sp = $saved_sp
|
||||
set $lr = $saved_lr
|
||||
set $pc = $saved_pc
|
||||
else
|
||||
printf "(not currently in exception handler)\n"
|
||||
end
|
||||
end
|
||||
|
||||
document vecstate
|
||||
. vecstate
|
||||
. Print information about the current exception handling state.
|
||||
end
|
|
@ -2,6 +2,7 @@
|
|||
# Various PX4-specific macros
|
||||
#
|
||||
source Debug/NuttX
|
||||
source Debug/ARMv7M
|
||||
|
||||
echo Loading PX4 GDB macros. Use 'help px4' for more information.\n
|
||||
|
||||
|
|
|
@ -7,6 +7,7 @@
|
|||
[
|
||||
"*.o",
|
||||
"*.a",
|
||||
"*.d",
|
||||
".built",
|
||||
".context",
|
||||
".depend",
|
||||
|
|
|
@ -1361,6 +1361,8 @@ int commander_thread_main(int argc, char *argv[])
|
|||
param_get(param_find("SYS_FAILSAVE_LL"), &failsafe_lowlevel_timeout_ms);
|
||||
|
||||
param_t _param_sys_type = param_find("MAV_TYPE");
|
||||
param_t _param_system_id = param_find("MAV_SYS_ID");
|
||||
param_t _param_component_id = param_find("MAV_COMP_ID");
|
||||
|
||||
/* welcome user */
|
||||
warnx("I am in command now!\n");
|
||||
|
@ -1558,6 +1560,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
/* parameters changed */
|
||||
orb_copy(ORB_ID(parameter_update), param_changed_sub, ¶m_changed);
|
||||
|
||||
|
||||
/* update parameters */
|
||||
if (!current_status.flag_system_armed) {
|
||||
if (param_get(_param_sys_type, &(current_status.system_type)) != OK) {
|
||||
|
@ -1573,6 +1576,11 @@ int commander_thread_main(int argc, char *argv[])
|
|||
} else {
|
||||
current_status.flag_external_manual_override_ok = true;
|
||||
}
|
||||
|
||||
/* check and update system / component ID */
|
||||
param_get(_param_system_id, &(current_status.system_id));
|
||||
param_get(_param_component_id, &(current_status.component_id));
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -322,7 +322,7 @@ void BlockMultiModeBacksideAutopilot::update()
|
|||
_att.roll, _att.pitch, _att.yaw,
|
||||
_att.rollspeed, _att.pitchspeed, _att.yawspeed
|
||||
);
|
||||
_actuators.control[CH_AIL] = - _backsideAutopilot.getAileron();
|
||||
_actuators.control[CH_AIL] = _backsideAutopilot.getAileron();
|
||||
_actuators.control[CH_ELV] = - _backsideAutopilot.getElevator();
|
||||
_actuators.control[CH_RDR] = _backsideAutopilot.getRudder();
|
||||
_actuators.control[CH_THR] = _backsideAutopilot.getThrottle();
|
||||
|
|
|
@ -127,7 +127,7 @@ class BlinkM : public device::I2C
|
|||
{
|
||||
public:
|
||||
BlinkM(int bus, int blinkm);
|
||||
~BlinkM();
|
||||
virtual ~BlinkM();
|
||||
|
||||
|
||||
virtual int init();
|
||||
|
|
|
@ -126,7 +126,7 @@ class BMA180 : public device::SPI
|
|||
{
|
||||
public:
|
||||
BMA180(int bus, spi_dev_e device);
|
||||
~BMA180();
|
||||
virtual ~BMA180();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
|
|
@ -74,8 +74,8 @@
|
|||
#define GPIO_ACC_OC_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_SERVO_OC_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
|
||||
|
||||
#define GPIO_RELAY1_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN13)
|
||||
#define GPIO_RELAY2_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_RELAY1_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN12)
|
||||
#define GPIO_RELAY2_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN11)
|
||||
|
||||
/* Analog inputs ********************************************************************/
|
||||
|
||||
|
|
|
@ -120,7 +120,7 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
|
|||
struct i2c_msg_s msgv[2];
|
||||
unsigned msgs;
|
||||
int ret;
|
||||
unsigned tries = 0;
|
||||
unsigned retry_count = 0;
|
||||
|
||||
do {
|
||||
// debug("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
|
||||
|
@ -154,16 +154,51 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
|
|||
I2C_SETFREQUENCY(_dev, _frequency);
|
||||
ret = I2C_TRANSFER(_dev, &msgv[0], msgs);
|
||||
|
||||
/* success */
|
||||
if (ret == OK)
|
||||
break;
|
||||
|
||||
// reset the I2C bus to unwedge on error
|
||||
/* if we have already retried once, or we are going to give up, then reset the bus */
|
||||
if ((retry_count >= 1) || (retry_count >= _retries))
|
||||
up_i2creset(_dev);
|
||||
|
||||
} while (tries++ < _retries);
|
||||
} while (retry_count++ < _retries);
|
||||
|
||||
return ret;
|
||||
|
||||
}
|
||||
|
||||
int
|
||||
I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
|
||||
{
|
||||
int ret;
|
||||
unsigned retry_count = 0;
|
||||
|
||||
/* force the device address into the message vector */
|
||||
for (unsigned i = 0; i < msgs; i++)
|
||||
msgv[i].addr = _address;
|
||||
|
||||
|
||||
do {
|
||||
/*
|
||||
* I2C architecture means there is an unavoidable race here
|
||||
* if there are any devices on the bus with a different frequency
|
||||
* preference. Really, this is pointless.
|
||||
*/
|
||||
I2C_SETFREQUENCY(_dev, _frequency);
|
||||
ret = I2C_TRANSFER(_dev, msgv, msgs);
|
||||
|
||||
/* success */
|
||||
if (ret == OK)
|
||||
break;
|
||||
|
||||
/* if we have already retried once, or we are going to give up, then reset the bus */
|
||||
if ((retry_count >= 1) || (retry_count >= _retries))
|
||||
up_i2creset(_dev);
|
||||
|
||||
} while (retry_count++ < _retries);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
} // namespace device
|
|
@ -100,6 +100,16 @@ protected:
|
|||
int transfer(const uint8_t *send, unsigned send_len,
|
||||
uint8_t *recv, unsigned recv_len);
|
||||
|
||||
/**
|
||||
* Perform a multi-part I2C transaction to the device.
|
||||
*
|
||||
* @param msgv An I2C message vector.
|
||||
* @param msgs The number of entries in the message vector.
|
||||
* @return OK if the transfer was successful, -errno
|
||||
* otherwise.
|
||||
*/
|
||||
int transfer(i2c_msg_s *msgv, unsigned msgs);
|
||||
|
||||
/**
|
||||
* Change the bus address.
|
||||
*
|
||||
|
|
|
@ -91,6 +91,22 @@ __EXPORT extern hrt_abstime ts_to_abstime(struct timespec *ts);
|
|||
*/
|
||||
__EXPORT extern void abstime_to_ts(struct timespec *ts, hrt_abstime abstime);
|
||||
|
||||
/*
|
||||
* Compute the delta between a timestamp taken in the past
|
||||
* and now.
|
||||
*
|
||||
* This function is safe to use even if the timestamp is updated
|
||||
* by an interrupt during execution.
|
||||
*/
|
||||
__EXPORT extern hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then);
|
||||
|
||||
/*
|
||||
* Store the absolute time in an interrupt-safe fashion.
|
||||
*
|
||||
* This function ensures that the timestamp cannot be seen half-written by an interrupt handler.
|
||||
*/
|
||||
__EXPORT extern hrt_abstime hrt_store_absolute_time(volatile hrt_abstime *now);
|
||||
|
||||
/*
|
||||
* Call callout(arg) after delay has elapsed.
|
||||
*
|
||||
|
|
|
@ -77,9 +77,6 @@ typedef uint16_t servo_position_t;
|
|||
* device.
|
||||
*/
|
||||
struct pwm_output_values {
|
||||
/** desired servo update rate in Hz */
|
||||
uint32_t update_rate;
|
||||
|
||||
/** desired pulse widths for each of the supported channels */
|
||||
servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
|
||||
};
|
||||
|
@ -106,6 +103,18 @@ ORB_DECLARE(output_pwm);
|
|||
/** set update rate in Hz */
|
||||
#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
|
||||
|
||||
/** get the number of servos in *(unsigned *)arg */
|
||||
#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 3)
|
||||
|
||||
/** set debug level for servo IO */
|
||||
#define PWM_SERVO_SET_DEBUG _IOC(_PWM_SERVO_BASE, 4)
|
||||
|
||||
/** enable in-air restart */
|
||||
#define PWM_SERVO_INAIR_RESTART_ENABLE _IOC(_PWM_SERVO_BASE, 5)
|
||||
|
||||
/** disable in-air restart */
|
||||
#define PWM_SERVO_INAIR_RESTART_DISABLE _IOC(_PWM_SERVO_BASE, 6)
|
||||
|
||||
/** set a single servo to a specific value */
|
||||
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
|
||||
|
||||
|
|
|
@ -0,0 +1,81 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file Rangefinder driver interface.
|
||||
*/
|
||||
|
||||
#ifndef _DRV_RANGEFINDER_H
|
||||
#define _DRV_RANGEFINDER_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#include "drv_sensor.h"
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder"
|
||||
|
||||
/**
|
||||
* range finder report structure. Reads from the device must be in multiples of this
|
||||
* structure.
|
||||
*/
|
||||
struct range_finder_report {
|
||||
uint64_t timestamp;
|
||||
float distance; /** in meters */
|
||||
uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
|
||||
};
|
||||
|
||||
/*
|
||||
* ObjDev tag for raw range finder data.
|
||||
*/
|
||||
ORB_DECLARE(sensor_range_finder);
|
||||
|
||||
/*
|
||||
* ioctl() definitions
|
||||
*
|
||||
* Rangefinder drivers also implement the generic sensor driver
|
||||
* interfaces from drv_sensor.h
|
||||
*/
|
||||
|
||||
#define _RANGEFINDERIOCBASE (0x7900)
|
||||
#define __RANGEFINDERIOC(_n) (_IOC(_RANGEFINDERIOCBASE, _n))
|
||||
|
||||
/** set the minimum effective distance of the device */
|
||||
#define RANGEFINDERIOCSETMINIUMDISTANCE __RANGEFINDERIOC(1)
|
||||
|
||||
/** set the maximum effective distance of the device */
|
||||
#define RANGEFINDERIOCSETMAXIUMDISTANCE __RANGEFINDERIOC(2)
|
||||
|
||||
|
||||
#endif /* _DRV_RANGEFINDER_H */
|
|
@ -100,4 +100,11 @@ struct rc_input_values {
|
|||
*/
|
||||
ORB_DECLARE(input_rc);
|
||||
|
||||
#define _RC_INPUT_BASE 0x2b00
|
||||
|
||||
/** Fetch R/C input values into (rc_input_values *)arg */
|
||||
|
||||
#define RC_INPUT_GET _IOC(_RC_INPUT_BASE, 0)
|
||||
|
||||
|
||||
#endif /* _DRV_RC_INPUT_H */
|
||||
|
|
|
@ -86,7 +86,7 @@ class GPS : public device::CDev
|
|||
{
|
||||
public:
|
||||
GPS(const char* uart_path);
|
||||
~GPS();
|
||||
virtual ~GPS();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
|
|
@ -91,7 +91,7 @@ public:
|
|||
MODE_NONE
|
||||
};
|
||||
HIL();
|
||||
~HIL();
|
||||
virtual ~HIL();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
|
||||
|
|
|
@ -130,7 +130,7 @@ class HMC5883 : public device::I2C
|
|||
{
|
||||
public:
|
||||
HMC5883(int bus);
|
||||
~HMC5883();
|
||||
virtual ~HMC5883();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
@ -465,7 +465,7 @@ HMC5883::probe()
|
|||
read_reg(ADDR_ID_C, data[2]))
|
||||
debug("read_reg fail");
|
||||
|
||||
_retries = 1;
|
||||
_retries = 2;
|
||||
|
||||
if ((data[0] != ID_A_WHO_AM_I) ||
|
||||
(data[1] != ID_B_WHO_AM_I) ||
|
||||
|
|
|
@ -152,7 +152,7 @@ class L3GD20 : public device::SPI
|
|||
{
|
||||
public:
|
||||
L3GD20(int bus, const char* path, spi_dev_e device);
|
||||
~L3GD20();
|
||||
virtual ~L3GD20();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
|
|
@ -53,7 +53,7 @@ class LED : device::CDev
|
|||
{
|
||||
public:
|
||||
LED();
|
||||
~LED();
|
||||
virtual ~LED();
|
||||
|
||||
virtual int init();
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
|
|
@ -0,0 +1,42 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2013 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the Maxbotix Sonar driver.
|
||||
#
|
||||
|
||||
APPNAME = mb12xx
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
|
@ -0,0 +1,840 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mb12xx.cpp
|
||||
* @author Greg Hulands
|
||||
*
|
||||
* Driver for the Maxbotix sonar range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
|
||||
/* Configuration Constants */
|
||||
#define MB12XX_BUS PX4_I2C_BUS_EXPANSION
|
||||
#define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */
|
||||
|
||||
/* MB12xx Registers addresses */
|
||||
|
||||
#define MB12XX_TAKE_RANGE_REG 0x51 /* Measure range Register */
|
||||
#define MB12XX_SET_ADDRESS_1 0xAA /* Change address 1 Register */
|
||||
#define MB12XX_SET_ADDRESS_2 0xA5 /* Change address 2 Register */
|
||||
|
||||
/* Device limits */
|
||||
#define MB12XX_MIN_DISTANCE (0.20f)
|
||||
#define MB12XX_MAX_DISTANCE (7.65f)
|
||||
|
||||
#define MB12XX_CONVERSION_INTERVAL 60000 /* 60ms */
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
class MB12XX : public device::I2C
|
||||
{
|
||||
public:
|
||||
MB12XX(int bus = MB12XX_BUS, int address = MB12XX_BASEADDR);
|
||||
virtual ~MB12XX();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
protected:
|
||||
virtual int probe();
|
||||
|
||||
private:
|
||||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
unsigned _num_reports;
|
||||
volatile unsigned _next_report;
|
||||
volatile unsigned _oldest_report;
|
||||
range_finder_report *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
|
||||
orb_advert_t _range_finder_topic;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/**
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
*
|
||||
* @param address The I2C bus address to probe.
|
||||
* @return True if the device is present.
|
||||
*/
|
||||
int probe_address(uint8_t address);
|
||||
|
||||
/**
|
||||
* Initialise the automatic measurement state machine and start it.
|
||||
*
|
||||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
void start();
|
||||
|
||||
/**
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Set the min and max distance thresholds if you want the end points of the sensors
|
||||
* range to be brought in at all, otherwise it will use the defaults MB12XX_MIN_DISTANCE
|
||||
* and MB12XX_MAX_DISTANCE
|
||||
*/
|
||||
void set_minimum_distance(float min);
|
||||
void set_maximum_distance(float max);
|
||||
float get_minimum_distance();
|
||||
float get_maximum_distance();
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
*/
|
||||
void cycle();
|
||||
int measure();
|
||||
int collect();
|
||||
/**
|
||||
* Static trampoline from the workq context; because we don't have a
|
||||
* generic workq wrapper yet.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
|
||||
};
|
||||
|
||||
/* helper macro for handling report buffer indices */
|
||||
#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int mb12xx_main(int argc, char *argv[]);
|
||||
|
||||
MB12XX::MB12XX(int bus, int address) :
|
||||
I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000),
|
||||
_min_distance(MB12XX_MIN_DISTANCE),
|
||||
_max_distance(MB12XX_MAX_DISTANCE),
|
||||
_num_reports(0),
|
||||
_next_report(0),
|
||||
_oldest_report(0),
|
||||
_reports(nullptr),
|
||||
_sensor_ok(false),
|
||||
_measure_ticks(0),
|
||||
_collect_phase(false),
|
||||
_range_finder_topic(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")),
|
||||
_buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows"))
|
||||
{
|
||||
// enable debug() calls
|
||||
_debug_enabled = true;
|
||||
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
|
||||
MB12XX::~MB12XX()
|
||||
{
|
||||
/* make sure we are truly inactive */
|
||||
stop();
|
||||
|
||||
/* free any existing reports */
|
||||
if (_reports != nullptr)
|
||||
delete[] _reports;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
|
||||
/* do I2C init (and probe) first */
|
||||
if (I2C::init() != OK)
|
||||
goto out;
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_num_reports = 2;
|
||||
_reports = new struct range_finder_report[_num_reports];
|
||||
|
||||
if (_reports == nullptr)
|
||||
goto out;
|
||||
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* get a publish handle on the range finder topic */
|
||||
memset(&_reports[0], 0, sizeof(_reports[0]));
|
||||
_range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &_reports[0]);
|
||||
|
||||
if (_range_finder_topic < 0)
|
||||
debug("failed to create sensor_range_finder object. Did you start uOrb?");
|
||||
|
||||
ret = OK;
|
||||
/* sensor is ok, but we don't really know if it is within range */
|
||||
_sensor_ok = true;
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::probe()
|
||||
{
|
||||
return measure();
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::set_minimum_distance(float min)
|
||||
{
|
||||
_min_distance = min;
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::set_maximum_distance(float max)
|
||||
{
|
||||
_max_distance = max;
|
||||
}
|
||||
|
||||
float
|
||||
MB12XX::get_minimum_distance()
|
||||
{
|
||||
return _min_distance;
|
||||
}
|
||||
|
||||
float
|
||||
MB12XX::get_maximum_distance()
|
||||
{
|
||||
return _max_distance;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
|
||||
case SENSORIOCSPOLLRATE: {
|
||||
switch (arg) {
|
||||
|
||||
/* switching to manual polling */
|
||||
case SENSOR_POLLRATE_MANUAL:
|
||||
stop();
|
||||
_measure_ticks = 0;
|
||||
return OK;
|
||||
|
||||
/* external signalling (DRDY) not supported */
|
||||
case SENSOR_POLLRATE_EXTERNAL:
|
||||
|
||||
/* zero would be bad */
|
||||
case 0:
|
||||
return -EINVAL;
|
||||
|
||||
/* set default/max polling rate */
|
||||
case SENSOR_POLLRATE_MAX:
|
||||
case SENSOR_POLLRATE_DEFAULT: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* set interval for next measurement to minimum legal value */
|
||||
_measure_ticks = USEC2TICK(MB12XX_CONVERSION_INTERVAL);
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* adjust to a legal polling interval in Hz */
|
||||
default: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* convert hz to tick interval via microseconds */
|
||||
unsigned ticks = USEC2TICK(1000000 / arg);
|
||||
|
||||
/* check against maximum rate */
|
||||
if (ticks < USEC2TICK(MB12XX_CONVERSION_INTERVAL))
|
||||
return -EINVAL;
|
||||
|
||||
/* update interval for next measurement */
|
||||
_measure_ticks = ticks;
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
case SENSORIOCGPOLLRATE:
|
||||
if (_measure_ticks == 0)
|
||||
return SENSOR_POLLRATE_MANUAL;
|
||||
|
||||
return (1000 / _measure_ticks);
|
||||
|
||||
case SENSORIOCSQUEUEDEPTH: {
|
||||
/* add one to account for the sentinel in the ring */
|
||||
arg++;
|
||||
|
||||
/* lower bound is mandatory, upper bound is a sanity check */
|
||||
if ((arg < 2) || (arg > 100))
|
||||
return -EINVAL;
|
||||
|
||||
/* allocate new buffer */
|
||||
struct range_finder_report *buf = new struct range_finder_report[arg];
|
||||
|
||||
if (nullptr == buf)
|
||||
return -ENOMEM;
|
||||
|
||||
/* reset the measurement state machine with the new buffer, free the old */
|
||||
stop();
|
||||
delete[] _reports;
|
||||
_num_reports = arg;
|
||||
_reports = buf;
|
||||
start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
case SENSORIOCGQUEUEDEPTH:
|
||||
return _num_reports - 1;
|
||||
|
||||
case SENSORIOCRESET:
|
||||
/* XXX implement this */
|
||||
return -EINVAL;
|
||||
|
||||
case RANGEFINDERIOCSETMINIUMDISTANCE:
|
||||
{
|
||||
set_minimum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
case RANGEFINDERIOCSETMAXIUMDISTANCE:
|
||||
{
|
||||
set_maximum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return I2C::ioctl(filp, cmd, arg);
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t
|
||||
MB12XX::read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
unsigned count = buflen / sizeof(struct range_finder_report);
|
||||
int ret = 0;
|
||||
|
||||
/* buffer must be large enough */
|
||||
if (count < 1)
|
||||
return -ENOSPC;
|
||||
|
||||
/* if automatic measurement is enabled */
|
||||
if (_measure_ticks > 0) {
|
||||
|
||||
/*
|
||||
* While there is space in the caller's buffer, and reports, copy them.
|
||||
* Note that we may be pre-empted by the workq thread while we are doing this;
|
||||
* we are careful to avoid racing with them.
|
||||
*/
|
||||
while (count--) {
|
||||
if (_oldest_report != _next_report) {
|
||||
memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
|
||||
ret += sizeof(_reports[0]);
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
}
|
||||
}
|
||||
|
||||
/* if there was no data, warn the caller */
|
||||
return ret ? ret : -EAGAIN;
|
||||
}
|
||||
|
||||
/* manual measurement - run one conversion */
|
||||
/* XXX really it'd be nice to lock against other readers here */
|
||||
do {
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* trigger a measurement */
|
||||
if (OK != measure()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* wait for it to complete */
|
||||
usleep(MB12XX_CONVERSION_INTERVAL);
|
||||
|
||||
/* run the collection phase */
|
||||
if (OK != collect()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* state machine will have generated a report, copy it out */
|
||||
memcpy(buffer, _reports, sizeof(*_reports));
|
||||
ret = sizeof(*_reports);
|
||||
|
||||
} while (0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::measure()
|
||||
{
|
||||
int ret;
|
||||
|
||||
/*
|
||||
* Send the command to begin a measurement.
|
||||
*/
|
||||
uint8_t cmd = MB12XX_TAKE_RANGE_REG;
|
||||
ret = transfer(&cmd, 1, nullptr, 0);
|
||||
|
||||
if (OK != ret)
|
||||
{
|
||||
perf_count(_comms_errors);
|
||||
log("i2c::transfer returned %d", ret);
|
||||
return ret;
|
||||
}
|
||||
ret = OK;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MB12XX::collect()
|
||||
{
|
||||
int ret = -EIO;
|
||||
|
||||
/* read from the sensor */
|
||||
uint8_t val[2] = {0, 0};
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
ret = transfer(nullptr, 0, &val[0], 2);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
log("error reading from sensor: %d", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint16_t distance = val[0] << 8 | val[1];
|
||||
float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */
|
||||
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
|
||||
_reports[_next_report].timestamp = hrt_absolute_time();
|
||||
_reports[_next_report].distance = si_units;
|
||||
_reports[_next_report].valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
|
||||
|
||||
/* publish it */
|
||||
orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &_reports[_next_report]);
|
||||
|
||||
/* post a report to the ring - note, not locked */
|
||||
INCREMENT(_next_report, _num_reports);
|
||||
|
||||
/* if we are running up against the oldest report, toss it */
|
||||
if (_next_report == _oldest_report) {
|
||||
perf_count(_buffer_overflows);
|
||||
INCREMENT(_oldest_report, _num_reports);
|
||||
}
|
||||
|
||||
/* notify anyone waiting for data */
|
||||
poll_notify(POLLIN);
|
||||
|
||||
ret = OK;
|
||||
|
||||
out:
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::start()
|
||||
{
|
||||
/* reset the report ring and state machine */
|
||||
_collect_phase = false;
|
||||
_oldest_report = _next_report = 0;
|
||||
|
||||
/* schedule a cycle to start things */
|
||||
work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 1);
|
||||
|
||||
/* notify about state change */
|
||||
struct subsystem_info_s info = {
|
||||
true,
|
||||
true,
|
||||
true,
|
||||
SUBSYSTEM_TYPE_RANGEFINDER};
|
||||
static orb_advert_t pub = -1;
|
||||
|
||||
if (pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), pub, &info);
|
||||
} else {
|
||||
pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::stop()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::cycle_trampoline(void *arg)
|
||||
{
|
||||
MB12XX *dev = (MB12XX *)arg;
|
||||
|
||||
dev->cycle();
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::cycle()
|
||||
{
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
log("collection error");
|
||||
/* restart the measurement state machine */
|
||||
start();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
|
||||
/*
|
||||
* Is there a collect->measure gap?
|
||||
*/
|
||||
if (_measure_ticks > USEC2TICK(MB12XX_CONVERSION_INTERVAL)) {
|
||||
|
||||
/* schedule a fresh cycle call when we are ready to measure again */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&MB12XX::cycle_trampoline,
|
||||
this,
|
||||
_measure_ticks - USEC2TICK(MB12XX_CONVERSION_INTERVAL));
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
if (OK != measure())
|
||||
log("measure error");
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&MB12XX::cycle_trampoline,
|
||||
this,
|
||||
USEC2TICK(MB12XX_CONVERSION_INTERVAL));
|
||||
}
|
||||
|
||||
void
|
||||
MB12XX::print_info()
|
||||
{
|
||||
perf_print_counter(_sample_perf);
|
||||
perf_print_counter(_comms_errors);
|
||||
perf_print_counter(_buffer_overflows);
|
||||
printf("poll interval: %u ticks\n", _measure_ticks);
|
||||
printf("report queue: %u (%u/%u @ %p)\n",
|
||||
_num_reports, _oldest_report, _next_report, _reports);
|
||||
}
|
||||
|
||||
/**
|
||||
* Local functions in support of the shell command.
|
||||
*/
|
||||
namespace mb12xx
|
||||
{
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
const int ERROR = -1;
|
||||
|
||||
MB12XX *g_dev;
|
||||
|
||||
void start();
|
||||
void stop();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
*/
|
||||
void
|
||||
start()
|
||||
{
|
||||
int fd;
|
||||
|
||||
if (g_dev != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new MB12XX(MB12XX_BUS);
|
||||
|
||||
if (g_dev == nullptr)
|
||||
goto fail;
|
||||
|
||||
if (OK != g_dev->init())
|
||||
goto fail;
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
goto fail;
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
goto fail;
|
||||
|
||||
exit(0);
|
||||
|
||||
fail:
|
||||
|
||||
if (g_dev != nullptr)
|
||||
{
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
errx(1, "driver start failed");
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the driver
|
||||
*/
|
||||
void stop()
|
||||
{
|
||||
if (g_dev != nullptr)
|
||||
{
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
else
|
||||
{
|
||||
errx(1, "driver not running");
|
||||
}
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform some basic functional tests on the driver;
|
||||
* make sure we can collect data from the sensor in polled
|
||||
* and automatic modes.
|
||||
*/
|
||||
void
|
||||
test()
|
||||
{
|
||||
struct range_finder_report report;
|
||||
ssize_t sz;
|
||||
int ret;
|
||||
|
||||
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_DEVICE_PATH);
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report))
|
||||
err(1, "immediate read failed");
|
||||
|
||||
warnx("single read");
|
||||
warnx("measurement: %0.2f m", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
|
||||
errx(1, "failed to set 2Hz poll rate");
|
||||
|
||||
/* read the sensor 5x and report each value */
|
||||
for (unsigned i = 0; i < 5; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
fds.fd = fd;
|
||||
fds.events = POLLIN;
|
||||
ret = poll(&fds, 1, 2000);
|
||||
|
||||
if (ret != 1)
|
||||
errx(1, "timed out waiting for sensor data");
|
||||
|
||||
/* now go get it */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report))
|
||||
err(1, "periodic read failed");
|
||||
|
||||
warnx("periodic read %u", i);
|
||||
warnx("measurement: %0.3f", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
}
|
||||
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
void
|
||||
reset()
|
||||
{
|
||||
int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "failed ");
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0)
|
||||
err(1, "driver reset failed");
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
|
||||
err(1, "driver poll restart failed");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print a little info about the driver.
|
||||
*/
|
||||
void
|
||||
info()
|
||||
{
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "driver not running");
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
int
|
||||
mb12xx_main(int argc, char *argv[])
|
||||
{
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "start"))
|
||||
mb12xx::start();
|
||||
|
||||
/*
|
||||
* Stop the driver
|
||||
*/
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
mb12xx::stop();
|
||||
|
||||
/*
|
||||
* Test the driver/device.
|
||||
*/
|
||||
if (!strcmp(argv[1], "test"))
|
||||
mb12xx::test();
|
||||
|
||||
/*
|
||||
* Reset the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "reset"))
|
||||
mb12xx::reset();
|
||||
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
|
||||
mb12xx::info();
|
||||
|
||||
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
|
||||
}
|
|
@ -151,7 +151,7 @@ class MPU6000 : public device::SPI
|
|||
{
|
||||
public:
|
||||
MPU6000(int bus, spi_dev_e device);
|
||||
~MPU6000();
|
||||
virtual ~MPU6000();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
|
|
@ -104,7 +104,7 @@ class MS5611 : public device::I2C
|
|||
{
|
||||
public:
|
||||
MS5611(int bus);
|
||||
~MS5611();
|
||||
virtual ~MS5611();
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
@ -144,6 +144,7 @@ private:
|
|||
orb_advert_t _baro_topic;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _measure_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
|
@ -162,12 +163,12 @@ private:
|
|||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
void start();
|
||||
void start_cycle();
|
||||
|
||||
/**
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
void stop();
|
||||
void stop_cycle();
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
|
@ -274,6 +275,7 @@ MS5611::MS5611(int bus) :
|
|||
_msl_pressure(101325),
|
||||
_baro_topic(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")),
|
||||
_measure_perf(perf_alloc(PC_ELAPSED, "ms5611_measure")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "ms5611_comms_errors")),
|
||||
_buffer_overflows(perf_alloc(PC_COUNT, "ms5611_buffer_overflows"))
|
||||
{
|
||||
|
@ -287,7 +289,7 @@ MS5611::MS5611(int bus) :
|
|||
MS5611::~MS5611()
|
||||
{
|
||||
/* make sure we are truly inactive */
|
||||
stop();
|
||||
stop_cycle();
|
||||
|
||||
/* free any existing reports */
|
||||
if (_reports != nullptr)
|
||||
|
@ -331,7 +333,11 @@ MS5611::probe()
|
|||
|
||||
if ((OK == probe_address(MS5611_ADDRESS_1)) ||
|
||||
(OK == probe_address(MS5611_ADDRESS_2))) {
|
||||
_retries = 1;
|
||||
/*
|
||||
* Disable retries; we may enable them selectively in some cases,
|
||||
* but the device gets confused if we retry some of the commands.
|
||||
*/
|
||||
_retries = 0;
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
@ -436,7 +442,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
|
||||
/* switching to manual polling */
|
||||
case SENSOR_POLLRATE_MANUAL:
|
||||
stop();
|
||||
stop_cycle();
|
||||
_measure_ticks = 0;
|
||||
return OK;
|
||||
|
||||
|
@ -458,7 +464,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
start_cycle();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
@ -480,7 +486,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start)
|
||||
start();
|
||||
start_cycle();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
@ -508,11 +514,11 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return -ENOMEM;
|
||||
|
||||
/* reset the measurement state machine with the new buffer, free the old */
|
||||
stop();
|
||||
stop_cycle();
|
||||
delete[] _reports;
|
||||
_num_reports = arg;
|
||||
_reports = buf;
|
||||
start();
|
||||
start_cycle();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
@ -545,7 +551,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
}
|
||||
|
||||
void
|
||||
MS5611::start()
|
||||
MS5611::start_cycle()
|
||||
{
|
||||
|
||||
/* reset the report ring and state machine */
|
||||
|
@ -558,7 +564,7 @@ MS5611::start()
|
|||
}
|
||||
|
||||
void
|
||||
MS5611::stop()
|
||||
MS5611::stop_cycle()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
}
|
||||
|
@ -574,15 +580,25 @@ MS5611::cycle_trampoline(void *arg)
|
|||
void
|
||||
MS5611::cycle()
|
||||
{
|
||||
int ret;
|
||||
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
log("collection error");
|
||||
ret = collect();
|
||||
if (ret != OK) {
|
||||
if (ret == -6) {
|
||||
/*
|
||||
* The ms5611 seems to regularly fail to respond to
|
||||
* its address; this happens often enough that we'd rather not
|
||||
* spam the console with the message.
|
||||
*/
|
||||
} else {
|
||||
log("collection error %d", ret);
|
||||
}
|
||||
/* reset the collection state machine and try again */
|
||||
start();
|
||||
start_cycle();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -609,8 +625,13 @@ MS5611::cycle()
|
|||
}
|
||||
|
||||
/* measurement phase */
|
||||
if (OK != measure())
|
||||
log("measure error");
|
||||
ret = measure();
|
||||
if (ret != OK) {
|
||||
log("measure error %d", ret);
|
||||
/* reset the collection state machine and try again */
|
||||
start_cycle();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
@ -628,6 +649,8 @@ MS5611::measure()
|
|||
{
|
||||
int ret;
|
||||
|
||||
perf_begin(_measure_perf);
|
||||
|
||||
/*
|
||||
* In phase zero, request temperature; in other phases, request pressure.
|
||||
*/
|
||||
|
@ -635,18 +658,25 @@ MS5611::measure()
|
|||
|
||||
/*
|
||||
* Send the command to begin measuring.
|
||||
*
|
||||
* Disable retries on this command; we can't know whether failure
|
||||
* means the device did or did not see the write.
|
||||
*/
|
||||
_retries = 0;
|
||||
ret = transfer(&cmd_data, 1, nullptr, 0);
|
||||
|
||||
if (OK != ret)
|
||||
perf_count(_comms_errors);
|
||||
|
||||
perf_end(_measure_perf);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
MS5611::collect()
|
||||
{
|
||||
int ret;
|
||||
uint8_t cmd;
|
||||
uint8_t data[3];
|
||||
union {
|
||||
|
@ -662,9 +692,11 @@ MS5611::collect()
|
|||
/* this should be fairly close to the end of the conversion, so the best approximation of the time */
|
||||
_reports[_next_report].timestamp = hrt_absolute_time();
|
||||
|
||||
if (OK != transfer(&cmd, 1, &data[0], 3)) {
|
||||
ret = transfer(&cmd, 1, &data[0], 3);
|
||||
if (ret != OK) {
|
||||
perf_count(_comms_errors);
|
||||
return -EIO;
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* fetch the raw value */
|
||||
|
|
|
@ -64,12 +64,14 @@
|
|||
#include <systemlib/err.h>
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
#include <drivers/drv_mixer.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_controls_effective.h>
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/ppm_decode.h>
|
||||
|
||||
class PX4FMU : public device::CDev
|
||||
{
|
||||
|
@ -80,9 +82,10 @@ public:
|
|||
MODE_NONE
|
||||
};
|
||||
PX4FMU();
|
||||
~PX4FMU();
|
||||
virtual ~PX4FMU();
|
||||
|
||||
virtual int ioctl(file *filp, int cmd, unsigned long arg);
|
||||
virtual ssize_t write(file *filp, const char *buffer, size_t len);
|
||||
|
||||
virtual int init();
|
||||
|
||||
|
@ -338,6 +341,13 @@ PX4FMU::task_main()
|
|||
|
||||
unsigned num_outputs = (_mode == MODE_2PWM) ? 2 : 4;
|
||||
|
||||
// rc input, published to ORB
|
||||
struct rc_input_values rc_in;
|
||||
orb_advert_t to_input_rc = 0;
|
||||
|
||||
memset(&rc_in, 0, sizeof(rc_in));
|
||||
rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM;
|
||||
|
||||
log("starting");
|
||||
|
||||
/* loop until killed */
|
||||
|
@ -363,8 +373,9 @@ PX4FMU::task_main()
|
|||
_current_update_rate = _update_rate;
|
||||
}
|
||||
|
||||
/* sleep waiting for data, but no more than a second */
|
||||
int ret = ::poll(&fds[0], 2, 1000);
|
||||
/* sleep waiting for data, stopping to check for PPM
|
||||
* input at 100Hz */
|
||||
int ret = ::poll(&fds[0], 2, 10);
|
||||
|
||||
/* this would be bad... */
|
||||
if (ret < 0) {
|
||||
|
@ -429,6 +440,26 @@ PX4FMU::task_main()
|
|||
/* update PWM servo armed status if armed and not locked down */
|
||||
up_pwm_servo_arm(aa.armed && !aa.lockdown);
|
||||
}
|
||||
|
||||
// see if we have new PPM input data
|
||||
if (ppm_last_valid_decode != rc_in.timestamp) {
|
||||
// we have a new PPM frame. Publish it.
|
||||
rc_in.channel_count = ppm_decoded_channels;
|
||||
if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) {
|
||||
rc_in.channel_count = RC_INPUT_MAX_CHANNELS;
|
||||
}
|
||||
for (uint8_t i=0; i<rc_in.channel_count; i++) {
|
||||
rc_in.values[i] = ppm_buffer[i];
|
||||
}
|
||||
rc_in.timestamp = ppm_last_valid_decode;
|
||||
|
||||
/* lazily advertise on first publication */
|
||||
if (to_input_rc == 0) {
|
||||
to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_in);
|
||||
} else {
|
||||
orb_publish(ORB_ID(input_rc), to_input_rc, &rc_in);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
::close(_t_actuators);
|
||||
|
@ -621,6 +652,30 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
return ret;
|
||||
}
|
||||
|
||||
/*
|
||||
this implements PWM output via a write() method, for compatibility
|
||||
with px4io
|
||||
*/
|
||||
ssize_t
|
||||
PX4FMU::write(file *filp, const char *buffer, size_t len)
|
||||
{
|
||||
unsigned count = len / 2;
|
||||
uint16_t values[4];
|
||||
|
||||
if (count > 4) {
|
||||
// we only have 4 PWM outputs on the FMU
|
||||
count = 4;
|
||||
}
|
||||
|
||||
// allow for misaligned values
|
||||
memcpy(values, buffer, count*2);
|
||||
|
||||
for (uint8_t i=0; i<count; i++) {
|
||||
up_pwm_servo_set(i, values[i]);
|
||||
}
|
||||
return count * 2;
|
||||
}
|
||||
|
||||
void
|
||||
PX4FMU::gpio_reset(void)
|
||||
{
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -46,7 +46,7 @@ class PX4IO_Uploader
|
|||
{
|
||||
public:
|
||||
PX4IO_Uploader();
|
||||
~PX4IO_Uploader();
|
||||
virtual ~PX4IO_Uploader();
|
||||
|
||||
int upload(const char *filenames[]);
|
||||
|
||||
|
|
|
@ -645,6 +645,36 @@ abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
|
|||
ts->tv_nsec = abstime * 1000;
|
||||
}
|
||||
|
||||
/*
|
||||
* Compare a time value with the current time.
|
||||
*/
|
||||
hrt_abstime
|
||||
hrt_elapsed_time(const volatile hrt_abstime *then)
|
||||
{
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
hrt_abstime delta = hrt_absolute_time() - *then;
|
||||
|
||||
irqrestore(flags);
|
||||
|
||||
return delta;
|
||||
}
|
||||
|
||||
/*
|
||||
* Store the absolute time in an interrupt-safe fashion
|
||||
*/
|
||||
hrt_abstime
|
||||
hrt_store_absolute_time(volatile hrt_abstime *now)
|
||||
{
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
hrt_abstime ts = hrt_absolute_time();
|
||||
|
||||
irqrestore(flags);
|
||||
|
||||
return ts;
|
||||
}
|
||||
|
||||
/*
|
||||
* Initalise the high-resolution timing module.
|
||||
*/
|
||||
|
|
|
@ -247,8 +247,8 @@ void KalmanNav::update()
|
|||
// output
|
||||
if (newTimeStamp - _outTimeStamp > 10e6) { // 0.1 Hz
|
||||
_outTimeStamp = newTimeStamp;
|
||||
printf("nav: %4d Hz, miss #: %4d\n",
|
||||
_navFrames / 10, _miss / 10);
|
||||
//printf("nav: %4d Hz, miss #: %4d\n",
|
||||
// _navFrames / 10, _miss / 10);
|
||||
_navFrames = 0;
|
||||
_miss = 0;
|
||||
}
|
||||
|
|
|
@ -63,7 +63,11 @@
|
|||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
#define mavlink_log_emergency(_fd, _text) ::ioctl(_fd, MAVLINK_IOC_SEND_TEXT_EMERGENCY, (unsigned long)_text);
|
||||
#else
|
||||
#define mavlink_log_emergency(_fd, _text) ioctl(_fd, MAVLINK_IOC_SEND_TEXT_EMERGENCY, (unsigned long)_text);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Send a mavlink critical message.
|
||||
|
@ -71,7 +75,11 @@
|
|||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
#define mavlink_log_critical(_fd, _text) ::ioctl(_fd, MAVLINK_IOC_SEND_TEXT_CRITICAL, (unsigned long)_text);
|
||||
#else
|
||||
#define mavlink_log_critical(_fd, _text) ioctl(_fd, MAVLINK_IOC_SEND_TEXT_CRITICAL, (unsigned long)_text);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Send a mavlink info message.
|
||||
|
@ -79,7 +87,11 @@
|
|||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
#ifdef __cplusplus
|
||||
#define mavlink_log_info(_fd, _text) ::ioctl(_fd, MAVLINK_IOC_SEND_TEXT_INFO, (unsigned long)_text);
|
||||
#else
|
||||
#define mavlink_log_info(_fd, _text) ioctl(_fd, MAVLINK_IOC_SEND_TEXT_INFO, (unsigned long)_text);
|
||||
#endif
|
||||
|
||||
struct mavlink_logmessage {
|
||||
char text[51];
|
||||
|
|
|
@ -511,32 +511,16 @@ l_actuator_outputs(struct listener *l)
|
|||
0);
|
||||
|
||||
} else {
|
||||
|
||||
/*
|
||||
* Catch the case where no rudder is in use and throttle is not
|
||||
* on output four
|
||||
*/
|
||||
float rudder, throttle;
|
||||
|
||||
if (act_outputs.noutputs < 4) {
|
||||
rudder = 0.0f;
|
||||
throttle = (act_outputs.output[2] - 900.0f) / 1200.0f;
|
||||
|
||||
} else {
|
||||
rudder = (act_outputs.output[2] - 1500.0f) / 600.0f;
|
||||
throttle = (act_outputs.output[3] - 900.0f) / 1200.0f;
|
||||
}
|
||||
|
||||
mavlink_msg_hil_controls_send(chan,
|
||||
hrt_absolute_time(),
|
||||
(act_outputs.output[0] - 1500.0f) / 600.0f,
|
||||
(act_outputs.output[1] - 1500.0f) / 600.0f,
|
||||
rudder,
|
||||
throttle,
|
||||
(act_outputs.output[4] - 1500.0f) / 600.0f,
|
||||
(act_outputs.output[5] - 1500.0f) / 600.0f,
|
||||
(act_outputs.output[6] - 1500.0f) / 600.0f,
|
||||
(act_outputs.output[7] - 1500.0f) / 600.0f,
|
||||
(act_outputs.output[0] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[1] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[2] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[3] - 1000.0f) / 1000.0f,
|
||||
(act_outputs.output[4] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[5] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[6] - 1500.0f) / 500.0f,
|
||||
(act_outputs.output[7] - 1500.0f) / 500.0f,
|
||||
mavlink_mode,
|
||||
0);
|
||||
}
|
||||
|
|
|
@ -498,7 +498,7 @@ int mavlink_onboard_main(int argc, char *argv[])
|
|||
mavlink_task = task_spawn("mavlink_onboard",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
6000 /* XXX probably excessive */,
|
||||
2048,
|
||||
mavlink_thread_main,
|
||||
(const char**)argv);
|
||||
exit(0);
|
||||
|
|
|
@ -55,6 +55,10 @@ config NSH_DISABLE_CP
|
|||
bool "Disable cp"
|
||||
default n
|
||||
|
||||
config NSH_DISABLE_CMP
|
||||
bool "Disable cmp"
|
||||
default n
|
||||
|
||||
config NSH_DISABLE_DD
|
||||
bool "Disable dd"
|
||||
default n
|
||||
|
|
|
@ -603,6 +603,9 @@ void nsh_usbtrace(void);
|
|||
# ifndef CONFIG_NSH_DISABLE_CP
|
||||
int cmd_cp(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
# endif
|
||||
# ifndef CONFIG_NSH_DISABLE_CMP
|
||||
int cmd_cmp(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
# endif
|
||||
# ifndef CONFIG_NSH_DISABLE_DD
|
||||
int cmd_dd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
|
||||
# endif
|
||||
|
|
|
@ -1232,3 +1232,84 @@ int cmd_sh(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
|
|||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
#ifndef CONFIG_NSH_DISABLE_CMP
|
||||
int cmd_cmp(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
|
||||
{
|
||||
char *path1 = NULL;
|
||||
char *path2 = NULL;
|
||||
int fd1 = -1, fd2 = -1;
|
||||
int ret = ERROR;
|
||||
unsigned total_read = 0;
|
||||
|
||||
/* Get the full path to the two files */
|
||||
|
||||
path1 = nsh_getfullpath(vtbl, argv[1]);
|
||||
if (!path1)
|
||||
{
|
||||
goto errout;
|
||||
}
|
||||
|
||||
path2 = nsh_getfullpath(vtbl, argv[2]);
|
||||
if (!path2)
|
||||
{
|
||||
goto errout;
|
||||
}
|
||||
|
||||
/* Open the files for reading */
|
||||
fd1 = open(path1, O_RDONLY);
|
||||
if (fd1 < 0)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
fd2 = open(path2, O_RDONLY);
|
||||
if (fd2 < 0)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, argv[0], "open", NSH_ERRNO);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
for (;;)
|
||||
{
|
||||
char buf1[128];
|
||||
char buf2[128];
|
||||
|
||||
int nbytesread1 = read(fd1, buf1, sizeof(buf1));
|
||||
int nbytesread2 = read(fd2, buf2, sizeof(buf2));
|
||||
|
||||
if (nbytesread1 < 0)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
if (nbytesread2 < 0)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, argv[0], "read", NSH_ERRNO);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
total_read += nbytesread1>nbytesread2?nbytesread2:nbytesread1;
|
||||
|
||||
if (nbytesread1 != nbytesread2 || memcmp(buf1, buf2, nbytesread1) != 0)
|
||||
{
|
||||
nsh_output(vtbl, "files differ: byte %u\n", total_read);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
if (nbytesread1 < sizeof(buf1)) break;
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
|
||||
errout:
|
||||
if (fd1 != -1) close(fd1);
|
||||
if (fd2 != -1) close(fd2);
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -175,6 +175,9 @@ static const struct cmdmap_s g_cmdmap[] =
|
|||
# ifndef CONFIG_NSH_DISABLE_CP
|
||||
{ "cp", cmd_cp, 3, 3, "<source-path> <dest-path>" },
|
||||
# endif
|
||||
# ifndef CONFIG_NSH_DISABLE_CMP
|
||||
{ "cmp", cmd_cmp, 3, 3, "<path1> <path2>" },
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#if defined (CONFIG_RTC) && !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_NSH_DISABLE_DATE)
|
||||
|
|
|
@ -39,11 +39,19 @@
|
|||
# Note that we pull a couple of specific files from the systemlib, since
|
||||
# we can't support it all.
|
||||
#
|
||||
CSRCS = $(wildcard *.c) \
|
||||
CSRCS = adc.c \
|
||||
controls.c \
|
||||
dsm.c \
|
||||
i2c.c \
|
||||
px4io.c \
|
||||
registers.c \
|
||||
safety.c \
|
||||
sbus.c \
|
||||
../systemlib/hx_stream.c \
|
||||
../systemlib/perf_counter.c \
|
||||
../systemlib/up_cxxinitialize.c
|
||||
CXXSRCS = $(wildcard *.cpp)
|
||||
|
||||
CXXSRCS = mixer.cpp
|
||||
|
||||
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
|
||||
|
||||
|
|
|
@ -154,7 +154,7 @@ adc_measure(unsigned channel)
|
|||
while (!(rSR & ADC_SR_EOC)) {
|
||||
|
||||
/* never spin forever - this will give a bogus result though */
|
||||
if ((hrt_absolute_time() - now) > 1000) {
|
||||
if (hrt_elapsed_time(&now) > 1000) {
|
||||
debug("adc timeout");
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -1,329 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file comms.c
|
||||
*
|
||||
* FMU communication for the PX4IO module.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <debug.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <string.h>
|
||||
#include <poll.h>
|
||||
#include <termios.h>
|
||||
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <systemlib/hx_stream.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
#define DEBUG
|
||||
#include "px4io.h"
|
||||
|
||||
#define FMU_MIN_REPORT_INTERVAL 5000 /* 5ms */
|
||||
#define FMU_MAX_REPORT_INTERVAL 100000 /* 100ms */
|
||||
|
||||
#define FMU_STATUS_INTERVAL 1000000 /* 100ms */
|
||||
|
||||
static int fmu_fd;
|
||||
static hx_stream_t stream;
|
||||
static struct px4io_report report;
|
||||
|
||||
static void comms_handle_frame(void *arg, const void *buffer, size_t length);
|
||||
|
||||
perf_counter_t comms_rx_errors;
|
||||
|
||||
static void
|
||||
comms_init(void)
|
||||
{
|
||||
/* initialise the FMU interface */
|
||||
fmu_fd = open("/dev/ttyS1", O_RDWR);
|
||||
stream = hx_stream_init(fmu_fd, comms_handle_frame, NULL);
|
||||
|
||||
comms_rx_errors = perf_alloc(PC_COUNT, "rx_err");
|
||||
hx_stream_set_counters(stream, 0, 0, comms_rx_errors);
|
||||
|
||||
/* default state in the report to FMU */
|
||||
report.i2f_magic = I2F_MAGIC;
|
||||
|
||||
struct termios t;
|
||||
|
||||
/* 115200bps, no parity, one stop bit */
|
||||
tcgetattr(fmu_fd, &t);
|
||||
cfsetspeed(&t, 115200);
|
||||
t.c_cflag &= ~(CSTOPB | PARENB);
|
||||
tcsetattr(fmu_fd, TCSANOW, &t);
|
||||
|
||||
/* init the ADC */
|
||||
adc_init();
|
||||
}
|
||||
|
||||
void
|
||||
comms_main(void)
|
||||
{
|
||||
comms_init();
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = fmu_fd;
|
||||
fds.events = POLLIN;
|
||||
debug("FMU: ready");
|
||||
|
||||
for (;;) {
|
||||
/* wait for serial data, but no more than 10ms */
|
||||
poll(&fds, 1, 10);
|
||||
|
||||
/*
|
||||
* Pull bytes from FMU and feed them to the HX engine.
|
||||
* Limit the number of bytes we actually process on any one iteration.
|
||||
*/
|
||||
if (fds.revents & POLLIN) {
|
||||
char buf[32];
|
||||
ssize_t count = read(fmu_fd, buf, sizeof(buf));
|
||||
|
||||
for (int i = 0; i < count; i++)
|
||||
hx_stream_rx(stream, buf[i]);
|
||||
}
|
||||
|
||||
/*
|
||||
* Decide if it's time to send an update to the FMU.
|
||||
*/
|
||||
static hrt_abstime last_report_time;
|
||||
hrt_abstime now, delta;
|
||||
|
||||
/* should we send a report to the FMU? */
|
||||
now = hrt_absolute_time();
|
||||
delta = now - last_report_time;
|
||||
|
||||
if ((delta > FMU_MIN_REPORT_INTERVAL) &&
|
||||
(system_state.fmu_report_due || (delta > FMU_MAX_REPORT_INTERVAL))) {
|
||||
|
||||
system_state.fmu_report_due = false;
|
||||
last_report_time = now;
|
||||
|
||||
/* populate the report */
|
||||
for (unsigned i = 0; i < system_state.rc_channels; i++) {
|
||||
report.rc_channel[i] = system_state.rc_channel_data[i];
|
||||
}
|
||||
|
||||
report.channel_count = system_state.rc_channels;
|
||||
report.armed = system_state.armed;
|
||||
|
||||
report.battery_mv = system_state.battery_mv;
|
||||
report.adc_in = system_state.adc_in5;
|
||||
report.overcurrent = system_state.overcurrent;
|
||||
|
||||
/* and send it */
|
||||
hx_stream_send(stream, &report, sizeof(report));
|
||||
}
|
||||
|
||||
/*
|
||||
* Fetch ADC values, check overcurrent flags, etc.
|
||||
*/
|
||||
static hrt_abstime last_status_time;
|
||||
|
||||
if ((now - last_status_time) > FMU_STATUS_INTERVAL) {
|
||||
|
||||
/*
|
||||
* Coefficients here derived by measurement of the 5-16V
|
||||
* range on one unit:
|
||||
*
|
||||
* V counts
|
||||
* 5 1001
|
||||
* 6 1219
|
||||
* 7 1436
|
||||
* 8 1653
|
||||
* 9 1870
|
||||
* 10 2086
|
||||
* 11 2303
|
||||
* 12 2522
|
||||
* 13 2738
|
||||
* 14 2956
|
||||
* 15 3172
|
||||
* 16 3389
|
||||
*
|
||||
* slope = 0.0046067
|
||||
* intercept = 0.3863
|
||||
*
|
||||
* Intercept corrected for best results @ 12V.
|
||||
*/
|
||||
unsigned counts = adc_measure(ADC_VBATT);
|
||||
system_state.battery_mv = (4150 + (counts * 46)) / 10;
|
||||
|
||||
system_state.adc_in5 = adc_measure(ADC_IN5);
|
||||
|
||||
system_state.overcurrent =
|
||||
(OVERCURRENT_SERVO ? (1 << 0) : 0) |
|
||||
(OVERCURRENT_ACC ? (1 << 1) : 0);
|
||||
|
||||
last_status_time = now;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
comms_handle_config(const void *buffer, size_t length)
|
||||
{
|
||||
const struct px4io_config *cfg = (struct px4io_config *)buffer;
|
||||
|
||||
if (length != sizeof(*cfg))
|
||||
return;
|
||||
|
||||
/* fetch the rc mappings */
|
||||
for (unsigned i = 0; i < 4; i++) {
|
||||
system_state.rc_map[i] = cfg->rc_map[i];
|
||||
}
|
||||
|
||||
/* fetch the rc channel attributes */
|
||||
for (unsigned i = 0; i < 4; i++) {
|
||||
system_state.rc_min[i] = cfg->rc_min[i];
|
||||
system_state.rc_trim[i] = cfg->rc_trim[i];
|
||||
system_state.rc_max[i] = cfg->rc_max[i];
|
||||
system_state.rc_rev[i] = cfg->rc_rev[i];
|
||||
system_state.rc_dz[i] = cfg->rc_dz[i];
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
comms_handle_command(const void *buffer, size_t length)
|
||||
{
|
||||
const struct px4io_command *cmd = (struct px4io_command *)buffer;
|
||||
|
||||
if (length != sizeof(*cmd))
|
||||
return;
|
||||
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
/* fetch new PWM output values */
|
||||
for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++)
|
||||
system_state.fmu_channel_data[i] = cmd->output_control[i];
|
||||
|
||||
/* if the IO is armed and the FMU gets disarmed, the IO must also disarm */
|
||||
if (system_state.arm_ok && !cmd->arm_ok)
|
||||
system_state.armed = false;
|
||||
|
||||
system_state.arm_ok = cmd->arm_ok;
|
||||
system_state.vector_flight_mode_ok = cmd->vector_flight_mode_ok;
|
||||
system_state.manual_override_ok = cmd->manual_override_ok;
|
||||
system_state.mixer_fmu_available = true;
|
||||
system_state.fmu_data_received_time = hrt_absolute_time();
|
||||
|
||||
/* set PWM update rate if changed (after limiting) */
|
||||
uint16_t new_servo_rate = cmd->servo_rate;
|
||||
|
||||
/* reject faster than 500 Hz updates */
|
||||
if (new_servo_rate > 500) {
|
||||
new_servo_rate = 500;
|
||||
}
|
||||
|
||||
/* reject slower than 50 Hz updates */
|
||||
if (new_servo_rate < 50) {
|
||||
new_servo_rate = 50;
|
||||
}
|
||||
|
||||
if (system_state.servo_rate != new_servo_rate) {
|
||||
up_pwm_servo_set_rate(new_servo_rate);
|
||||
system_state.servo_rate = new_servo_rate;
|
||||
}
|
||||
|
||||
/*
|
||||
* update servo values immediately.
|
||||
* the updates are done in addition also
|
||||
* in the mainloop, since this function will only
|
||||
* update with a connected FMU.
|
||||
*/
|
||||
mixer_tick();
|
||||
|
||||
/* handle relay state changes here */
|
||||
for (unsigned i = 0; i < PX4IO_RELAY_CHANNELS; i++) {
|
||||
if (system_state.relays[i] != cmd->relay_state[i]) {
|
||||
switch (i) {
|
||||
case 0:
|
||||
POWER_ACC1(cmd->relay_state[i]);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
POWER_ACC2(cmd->relay_state[i]);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
POWER_RELAY1(cmd->relay_state[i]);
|
||||
break;
|
||||
|
||||
case 3:
|
||||
POWER_RELAY2(cmd->relay_state[i]);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
system_state.relays[i] = cmd->relay_state[i];
|
||||
}
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
|
||||
static void
|
||||
comms_handle_frame(void *arg, const void *buffer, size_t length)
|
||||
{
|
||||
const uint16_t *type = (const uint16_t *)buffer;
|
||||
|
||||
|
||||
/* make sure it's what we are expecting */
|
||||
if (length > 2) {
|
||||
switch (*type) {
|
||||
case F2I_MAGIC:
|
||||
comms_handle_command(buffer, length);
|
||||
break;
|
||||
|
||||
case F2I_CONFIG_MAGIC:
|
||||
comms_handle_config(buffer, length);
|
||||
break;
|
||||
|
||||
case F2I_MIXER_MAGIC:
|
||||
mixer_handle_text(buffer, length);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -37,51 +37,54 @@
|
|||
* R/C inputs and servo outputs.
|
||||
*/
|
||||
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <debug.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <termios.h>
|
||||
#include <string.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <systemlib/hx_stream.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/ppm_decode.h>
|
||||
|
||||
#define DEBUG
|
||||
#include "px4io.h"
|
||||
|
||||
#define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */
|
||||
#define RC_CHANNEL_HIGH_THRESH 1700
|
||||
#define RC_CHANNEL_LOW_THRESH 1300
|
||||
#define RC_CHANNEL_HIGH_THRESH 5000
|
||||
#define RC_CHANNEL_LOW_THRESH -5000
|
||||
|
||||
static void ppm_input(void);
|
||||
static bool ppm_input(uint16_t *values, uint16_t *num_values);
|
||||
|
||||
static perf_counter_t c_gather_dsm;
|
||||
static perf_counter_t c_gather_sbus;
|
||||
static perf_counter_t c_gather_ppm;
|
||||
|
||||
void
|
||||
controls_main(void)
|
||||
controls_init(void)
|
||||
{
|
||||
struct pollfd fds[2];
|
||||
|
||||
/* DSM input */
|
||||
fds[0].fd = dsm_init("/dev/ttyS0");
|
||||
fds[0].events = POLLIN;
|
||||
dsm_init("/dev/ttyS0");
|
||||
|
||||
/* S.bus input */
|
||||
fds[1].fd = sbus_init("/dev/ttyS2");
|
||||
fds[1].events = POLLIN;
|
||||
sbus_init("/dev/ttyS2");
|
||||
|
||||
for (;;) {
|
||||
/* run this loop at ~100Hz */
|
||||
poll(fds, 2, 10);
|
||||
/* default to a 1:1 input map, all enabled */
|
||||
for (unsigned i = 0; i < MAX_CONTROL_CHANNELS; i++) {
|
||||
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
||||
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = 0;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 1000;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_CENTER] = 1500;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MAX] = 2000;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_DEADZONE] = 30;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_ASSIGNMENT] = i;
|
||||
r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
|
||||
}
|
||||
|
||||
c_gather_dsm = perf_alloc(PC_ELAPSED, "c_gather_dsm");
|
||||
c_gather_sbus = perf_alloc(PC_ELAPSED, "c_gather_sbus");
|
||||
c_gather_ppm = perf_alloc(PC_ELAPSED, "c_gather_ppm");
|
||||
}
|
||||
|
||||
void
|
||||
controls_tick() {
|
||||
|
||||
/*
|
||||
* Gather R/C control inputs from supported sources.
|
||||
|
@ -90,95 +93,236 @@ controls_main(void)
|
|||
* one control input source, they're going to fight each
|
||||
* other. Don't do that.
|
||||
*/
|
||||
bool locked = false;
|
||||
|
||||
perf_begin(c_gather_dsm);
|
||||
bool dsm_updated = dsm_input(r_raw_rc_values, &r_raw_rc_count);
|
||||
if (dsm_updated)
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
|
||||
perf_end(c_gather_dsm);
|
||||
|
||||
perf_begin(c_gather_sbus);
|
||||
bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count);
|
||||
if (sbus_updated)
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
|
||||
perf_end(c_gather_sbus);
|
||||
|
||||
/*
|
||||
* Store RC channel count to detect switch to RC loss sooner
|
||||
* than just by timeout
|
||||
*/
|
||||
unsigned rc_channels = system_state.rc_channels;
|
||||
|
||||
if (fds[0].revents & POLLIN)
|
||||
locked |= dsm_input();
|
||||
|
||||
if (fds[1].revents & POLLIN)
|
||||
locked |= sbus_input();
|
||||
|
||||
/*
|
||||
* If we don't have lock from one of the serial receivers,
|
||||
* look for PPM. It shares an input with S.bus, so there's
|
||||
* a possibility it will mis-parse an S.bus frame.
|
||||
*
|
||||
* XXX each S.bus frame will cause a PPM decoder interrupt
|
||||
* storm (lots of edges). It might be sensible to actually
|
||||
* disable the PPM decoder completely if we have an alternate
|
||||
* receiver lock.
|
||||
* disable the PPM decoder completely if we have S.bus signal.
|
||||
*/
|
||||
if (!locked)
|
||||
ppm_input();
|
||||
perf_begin(c_gather_ppm);
|
||||
bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count);
|
||||
if (ppm_updated)
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
|
||||
perf_end(c_gather_ppm);
|
||||
|
||||
/* check for manual override status */
|
||||
if (system_state.rc_channel_data[4] > RC_CHANNEL_HIGH_THRESH) {
|
||||
/* force manual input override */
|
||||
system_state.mixer_manual_override = true;
|
||||
ASSERT(r_raw_rc_count <= MAX_CONTROL_CHANNELS);
|
||||
|
||||
/*
|
||||
* In some cases we may have received a frame, but input has still
|
||||
* been lost.
|
||||
*/
|
||||
bool rc_input_lost = false;
|
||||
|
||||
/*
|
||||
* If we received a new frame from any of the RC sources, process it.
|
||||
*/
|
||||
if (dsm_updated || sbus_updated || ppm_updated) {
|
||||
|
||||
/* update RC-received timestamp */
|
||||
system_state.rc_channels_timestamp = hrt_absolute_time();
|
||||
|
||||
/* record a bitmask of channels assigned */
|
||||
unsigned assigned_channels = 0;
|
||||
|
||||
/* map raw inputs to mapped inputs */
|
||||
/* XXX mapping should be atomic relative to protocol */
|
||||
for (unsigned i = 0; i < r_raw_rc_count; i++) {
|
||||
|
||||
/* map the input channel */
|
||||
uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
|
||||
|
||||
if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
|
||||
|
||||
uint16_t raw = r_raw_rc_values[i];
|
||||
|
||||
int16_t scaled;
|
||||
|
||||
/*
|
||||
* 1) Constrain to min/max values, as later processing depends on bounds.
|
||||
*/
|
||||
if (raw < conf[PX4IO_P_RC_CONFIG_MIN])
|
||||
raw = conf[PX4IO_P_RC_CONFIG_MIN];
|
||||
if (raw > conf[PX4IO_P_RC_CONFIG_MAX])
|
||||
raw = conf[PX4IO_P_RC_CONFIG_MAX];
|
||||
|
||||
/*
|
||||
* 2) Scale around the mid point differently for lower and upper range.
|
||||
*
|
||||
* This is necessary as they don't share the same endpoints and slope.
|
||||
*
|
||||
* First normalize to 0..1 range with correct sign (below or above center),
|
||||
* then scale to 20000 range (if center is an actual center, -10000..10000,
|
||||
* if parameters only support half range, scale to 10000 range, e.g. if
|
||||
* center == min 0..10000, if center == max -10000..0).
|
||||
*
|
||||
* As the min and max bounds were enforced in step 1), division by zero
|
||||
* cannot occur, as for the case of center == min or center == max the if
|
||||
* statement is mutually exclusive with the arithmetic NaN case.
|
||||
*
|
||||
* DO NOT REMOVE OR ALTER STEP 1!
|
||||
*/
|
||||
if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
|
||||
|
||||
} else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
|
||||
|
||||
} else {
|
||||
/* override not engaged, use FMU */
|
||||
system_state.mixer_manual_override = false;
|
||||
/* in the configured dead zone, output zero */
|
||||
scaled = 0;
|
||||
}
|
||||
|
||||
/* invert channel if requested */
|
||||
if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE)
|
||||
scaled = -scaled;
|
||||
|
||||
/* and update the scaled/mapped version */
|
||||
unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
|
||||
ASSERT(mapped < MAX_CONTROL_CHANNELS);
|
||||
|
||||
r_rc_values[mapped] = SIGNED_TO_REG(scaled);
|
||||
assigned_channels |= (1 << mapped);
|
||||
}
|
||||
}
|
||||
|
||||
/* set un-assigned controls to zero */
|
||||
for (unsigned i = 0; i < MAX_CONTROL_CHANNELS; i++) {
|
||||
if (!(assigned_channels & (1 << i)))
|
||||
r_rc_values[i] = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* If we got an update with zero channels, treat it as
|
||||
* a loss of input.
|
||||
*
|
||||
* This might happen if a protocol-based receiver returns an update
|
||||
* that contains no channels that we have mapped.
|
||||
*/
|
||||
if (assigned_channels == 0) {
|
||||
rc_input_lost = true;
|
||||
} else {
|
||||
/* set RC OK flag and clear RC lost alarm */
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
|
||||
r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_RC_LOST;
|
||||
}
|
||||
|
||||
/*
|
||||
* Export the valid channel bitmap
|
||||
*/
|
||||
r_rc_valid = assigned_channels;
|
||||
}
|
||||
|
||||
/*
|
||||
* If we haven't seen any new control data in 200ms, assume we
|
||||
* have lost input and tell FMU.
|
||||
* have lost input.
|
||||
*/
|
||||
if ((hrt_absolute_time() - system_state.rc_channels_timestamp) > 200000) {
|
||||
if (hrt_elapsed_time(&system_state.rc_channels_timestamp) > 200000) {
|
||||
rc_input_lost = true;
|
||||
|
||||
if (system_state.rc_channels > 0) {
|
||||
/*
|
||||
* If the RC signal status (lost / present) has
|
||||
* just changed, request an update immediately.
|
||||
*/
|
||||
system_state.fmu_report_due = true;
|
||||
}
|
||||
|
||||
/* set the number of channels to zero - no inputs */
|
||||
system_state.rc_channels = 0;
|
||||
/* clear the input-kind flags here */
|
||||
r_status_flags &= ~(
|
||||
PX4IO_P_STATUS_FLAGS_RC_PPM |
|
||||
PX4IO_P_STATUS_FLAGS_RC_DSM |
|
||||
PX4IO_P_STATUS_FLAGS_RC_SBUS);
|
||||
}
|
||||
|
||||
/*
|
||||
* PWM output updates are performed in addition on each comm update.
|
||||
* the updates here are required to ensure operation if FMU is not started
|
||||
* or stopped responding.
|
||||
* Handle losing RC input
|
||||
*/
|
||||
if (rc_input_lost) {
|
||||
|
||||
/* Clear the RC input status flag, clear manual override flag */
|
||||
r_status_flags &= ~(
|
||||
PX4IO_P_STATUS_FLAGS_OVERRIDE |
|
||||
PX4IO_P_STATUS_FLAGS_RC_OK);
|
||||
|
||||
/* Set the RC_LOST alarm */
|
||||
r_status_alarms |= PX4IO_P_STATUS_ALARMS_RC_LOST;
|
||||
|
||||
/* Mark the arrays as empty */
|
||||
r_raw_rc_count = 0;
|
||||
r_rc_valid = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Check for manual override.
|
||||
*
|
||||
* The PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK flag must be set, and we
|
||||
* must have R/C input.
|
||||
* Override is enabled if either the hardcoded channel / value combination
|
||||
* is selected, or the AP has requested it.
|
||||
*/
|
||||
if ((r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK)) {
|
||||
|
||||
bool override = false;
|
||||
|
||||
/*
|
||||
* Check mapped channel 5 (can be any remote channel,
|
||||
* depends on RC_MAP_OVER parameter);
|
||||
* If the value is 'high' then the pilot has
|
||||
* requested override.
|
||||
*
|
||||
*/
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) > RC_CHANNEL_HIGH_THRESH))
|
||||
override = true;
|
||||
|
||||
if (override) {
|
||||
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE;
|
||||
|
||||
/* mix new RC input control values to servos */
|
||||
if (dsm_updated || sbus_updated || ppm_updated)
|
||||
mixer_tick();
|
||||
|
||||
} else {
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
ppm_input(void)
|
||||
static bool
|
||||
ppm_input(uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
/*
|
||||
* Look for new PPM input.
|
||||
*/
|
||||
if (ppm_last_valid_decode != 0) {
|
||||
bool result = false;
|
||||
|
||||
/* avoid racing with PPM updates */
|
||||
irqstate_t state = irqsave();
|
||||
|
||||
/*
|
||||
* If we have received a new PPM frame within the last 200ms, accept it
|
||||
* and then invalidate it.
|
||||
*/
|
||||
if (hrt_elapsed_time(&ppm_last_valid_decode) < 200000) {
|
||||
|
||||
/* PPM data exists, copy it */
|
||||
system_state.rc_channels = ppm_decoded_channels;
|
||||
*num_values = ppm_decoded_channels;
|
||||
if (*num_values > MAX_CONTROL_CHANNELS)
|
||||
*num_values = MAX_CONTROL_CHANNELS;
|
||||
|
||||
for (unsigned i = 0; i < ppm_decoded_channels; i++) {
|
||||
system_state.rc_channel_data[i] = ppm_buffer[i];
|
||||
}
|
||||
for (unsigned i = 0; i < *num_values; i++)
|
||||
values[i] = ppm_buffer[i];
|
||||
|
||||
/* copy the timestamp and clear it */
|
||||
system_state.rc_channels_timestamp = ppm_last_valid_decode;
|
||||
/* clear validity */
|
||||
ppm_last_valid_decode = 0;
|
||||
|
||||
/* good if we got any channels */
|
||||
result = (*num_values > 0);
|
||||
}
|
||||
|
||||
irqrestore(state);
|
||||
|
||||
/* trigger an immediate report to the FMU */
|
||||
system_state.fmu_report_due = true;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
|
|
@ -43,17 +43,13 @@
|
|||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
|
||||
#include <systemlib/ppm_decode.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#define DEBUG
|
||||
|
||||
#include "px4io.h"
|
||||
#include "protocol.h"
|
||||
|
||||
#define DSM_FRAME_SIZE 16
|
||||
#define DSM_FRAME_CHANNELS 7
|
||||
|
@ -72,13 +68,13 @@ unsigned dsm_frame_drops;
|
|||
|
||||
static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value);
|
||||
static void dsm_guess_format(bool reset);
|
||||
static void dsm_decode(hrt_abstime now);
|
||||
static bool dsm_decode(hrt_abstime now, uint16_t *values, uint16_t *num_values);
|
||||
|
||||
int
|
||||
dsm_init(const char *device)
|
||||
{
|
||||
if (dsm_fd < 0)
|
||||
dsm_fd = open(device, O_RDONLY);
|
||||
dsm_fd = open(device, O_RDONLY | O_NONBLOCK);
|
||||
|
||||
if (dsm_fd >= 0) {
|
||||
struct termios t;
|
||||
|
@ -106,7 +102,7 @@ dsm_init(const char *device)
|
|||
}
|
||||
|
||||
bool
|
||||
dsm_input(void)
|
||||
dsm_input(uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
ssize_t ret;
|
||||
hrt_abstime now;
|
||||
|
@ -143,7 +139,7 @@ dsm_input(void)
|
|||
|
||||
/* if the read failed for any reason, just give up here */
|
||||
if (ret < 1)
|
||||
goto out;
|
||||
return false;
|
||||
|
||||
last_rx_time = now;
|
||||
|
||||
|
@ -156,20 +152,14 @@ dsm_input(void)
|
|||
* If we don't have a full frame, return
|
||||
*/
|
||||
if (partial_frame_count < DSM_FRAME_SIZE)
|
||||
goto out;
|
||||
return false;
|
||||
|
||||
/*
|
||||
* Great, it looks like we might have a frame. Go ahead and
|
||||
* decode it.
|
||||
*/
|
||||
dsm_decode(now);
|
||||
partial_frame_count = 0;
|
||||
|
||||
out:
|
||||
/*
|
||||
* If we have seen a frame in the last 200ms, we consider ourselves 'locked'
|
||||
*/
|
||||
return (now - last_frame_time) < 200000;
|
||||
return dsm_decode(now, values, num_values);
|
||||
}
|
||||
|
||||
static bool
|
||||
|
@ -259,23 +249,23 @@ dsm_guess_format(bool reset)
|
|||
|
||||
if ((votes11 == 1) && (votes10 == 0)) {
|
||||
channel_shift = 11;
|
||||
debug("DSM: detected 11-bit format");
|
||||
debug("DSM: 11-bit format");
|
||||
return;
|
||||
}
|
||||
|
||||
if ((votes10 == 1) && (votes11 == 0)) {
|
||||
channel_shift = 10;
|
||||
debug("DSM: detected 10-bit format");
|
||||
debug("DSM: 10-bit format");
|
||||
return;
|
||||
}
|
||||
|
||||
/* call ourselves to reset our state ... we have to try again */
|
||||
debug("DSM: format detector failed, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
|
||||
debug("DSM: format detect fail, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
|
||||
dsm_guess_format(true);
|
||||
}
|
||||
|
||||
static void
|
||||
dsm_decode(hrt_abstime frame_time)
|
||||
static bool
|
||||
dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
|
||||
/*
|
||||
|
@ -296,7 +286,7 @@ dsm_decode(hrt_abstime frame_time)
|
|||
/* if we don't know the frame format, update the guessing state machine */
|
||||
if (channel_shift == 0) {
|
||||
dsm_guess_format(false);
|
||||
return;
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -324,8 +314,8 @@ dsm_decode(hrt_abstime frame_time)
|
|||
continue;
|
||||
|
||||
/* update the decoded channel count */
|
||||
if (channel >= system_state.rc_channels)
|
||||
system_state.rc_channels = channel + 1;
|
||||
if (channel >= *num_values)
|
||||
*num_values = channel + 1;
|
||||
|
||||
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
|
||||
if (channel_shift == 11)
|
||||
|
@ -356,13 +346,11 @@ dsm_decode(hrt_abstime frame_time)
|
|||
break;
|
||||
}
|
||||
|
||||
system_state.rc_channel_data[channel] = value;
|
||||
values[channel] = value;
|
||||
}
|
||||
|
||||
/* and note that we have received data from the R/C controller */
|
||||
/* XXX failsafe will cause problems here - need a strategy for detecting it */
|
||||
system_state.rc_channels_timestamp = frame_time;
|
||||
|
||||
/* trigger an immediate report to the FMU */
|
||||
system_state.fmu_report_due = true;
|
||||
/*
|
||||
* XXX Note that we may be in failsafe here; we need to work out how to detect that.
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -0,0 +1,340 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file i2c.c
|
||||
*
|
||||
* I2C communication for the PX4IO module.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <stm32_i2c.h>
|
||||
#include <stm32_dma.h>
|
||||
|
||||
//#define DEBUG
|
||||
#include "px4io.h"
|
||||
|
||||
/*
|
||||
* I2C register definitions.
|
||||
*/
|
||||
#define I2C_BASE STM32_I2C1_BASE
|
||||
|
||||
#define REG(_reg) (*(volatile uint32_t *)(I2C_BASE + _reg))
|
||||
|
||||
#define rCR1 REG(STM32_I2C_CR1_OFFSET)
|
||||
#define rCR2 REG(STM32_I2C_CR2_OFFSET)
|
||||
#define rOAR1 REG(STM32_I2C_OAR1_OFFSET)
|
||||
#define rOAR2 REG(STM32_I2C_OAR2_OFFSET)
|
||||
#define rDR REG(STM32_I2C_DR_OFFSET)
|
||||
#define rSR1 REG(STM32_I2C_SR1_OFFSET)
|
||||
#define rSR2 REG(STM32_I2C_SR2_OFFSET)
|
||||
#define rCCR REG(STM32_I2C_CCR_OFFSET)
|
||||
#define rTRISE REG(STM32_I2C_TRISE_OFFSET)
|
||||
|
||||
static int i2c_interrupt(int irq, void *context);
|
||||
static void i2c_rx_setup(void);
|
||||
static void i2c_tx_setup(void);
|
||||
static void i2c_rx_complete(void);
|
||||
static void i2c_tx_complete(void);
|
||||
|
||||
static DMA_HANDLE rx_dma;
|
||||
static DMA_HANDLE tx_dma;
|
||||
|
||||
static uint8_t rx_buf[68];
|
||||
static unsigned rx_len;
|
||||
|
||||
static const uint8_t junk_buf[] = { 0xff, 0xff, 0xff, 0xff };
|
||||
|
||||
static const uint8_t *tx_buf = junk_buf;
|
||||
static unsigned tx_len = sizeof(junk_buf);
|
||||
unsigned tx_count;
|
||||
|
||||
static uint8_t selected_page;
|
||||
static uint8_t selected_offset;
|
||||
|
||||
enum {
|
||||
DIR_NONE = 0,
|
||||
DIR_TX = 1,
|
||||
DIR_RX = 2
|
||||
} direction;
|
||||
|
||||
void
|
||||
i2c_init(void)
|
||||
{
|
||||
debug("i2c init");
|
||||
|
||||
/* allocate DMA handles and initialise DMA */
|
||||
rx_dma = stm32_dmachannel(DMACHAN_I2C1_RX);
|
||||
i2c_rx_setup();
|
||||
tx_dma = stm32_dmachannel(DMACHAN_I2C1_TX);
|
||||
i2c_tx_setup();
|
||||
|
||||
/* enable the i2c block clock and reset it */
|
||||
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
|
||||
modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST);
|
||||
modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0);
|
||||
|
||||
/* configure the i2c GPIOs */
|
||||
stm32_configgpio(GPIO_I2C1_SCL);
|
||||
stm32_configgpio(GPIO_I2C1_SDA);
|
||||
|
||||
/* soft-reset the block */
|
||||
rCR1 |= I2C_CR1_SWRST;
|
||||
rCR1 = 0;
|
||||
|
||||
/* set for DMA operation */
|
||||
rCR2 |= I2C_CR2_ITEVFEN |I2C_CR2_ITERREN | I2C_CR2_DMAEN;
|
||||
|
||||
/* set the frequency value in CR2 */
|
||||
rCR2 &= ~I2C_CR2_FREQ_MASK;
|
||||
rCR2 |= STM32_PCLK1_FREQUENCY / 1000000;
|
||||
|
||||
/* set divisor and risetime for fast mode */
|
||||
uint16_t result = STM32_PCLK1_FREQUENCY / (400000 * 25);
|
||||
if (result < 1)
|
||||
result = 1;
|
||||
result = 3;
|
||||
rCCR &= ~I2C_CCR_CCR_MASK;
|
||||
rCCR |= I2C_CCR_DUTY | I2C_CCR_FS | result;
|
||||
rTRISE = (uint16_t)((((STM32_PCLK1_FREQUENCY / 1000000) * 300) / 1000) + 1);
|
||||
|
||||
/* set our device address */
|
||||
rOAR1 = 0x1a << 1;
|
||||
|
||||
/* enable event interrupts */
|
||||
irq_attach(STM32_IRQ_I2C1EV, i2c_interrupt);
|
||||
irq_attach(STM32_IRQ_I2C1ER, i2c_interrupt);
|
||||
up_enable_irq(STM32_IRQ_I2C1EV);
|
||||
up_enable_irq(STM32_IRQ_I2C1ER);
|
||||
|
||||
/* and enable the I2C port */
|
||||
rCR1 |= I2C_CR1_ACK | I2C_CR1_PE;
|
||||
|
||||
#ifdef DEBUG
|
||||
i2c_dump();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
reset the I2C bus
|
||||
used to recover from lockups
|
||||
*/
|
||||
void i2c_reset(void)
|
||||
{
|
||||
rCR1 |= I2C_CR1_SWRST;
|
||||
rCR1 = 0;
|
||||
|
||||
/* set for DMA operation */
|
||||
rCR2 |= I2C_CR2_ITEVFEN |I2C_CR2_ITERREN | I2C_CR2_DMAEN;
|
||||
|
||||
/* set the frequency value in CR2 */
|
||||
rCR2 &= ~I2C_CR2_FREQ_MASK;
|
||||
rCR2 |= STM32_PCLK1_FREQUENCY / 1000000;
|
||||
|
||||
/* set divisor and risetime for fast mode */
|
||||
uint16_t result = STM32_PCLK1_FREQUENCY / (400000 * 25);
|
||||
if (result < 1)
|
||||
result = 1;
|
||||
result = 3;
|
||||
rCCR &= ~I2C_CCR_CCR_MASK;
|
||||
rCCR |= I2C_CCR_DUTY | I2C_CCR_FS | result;
|
||||
rTRISE = (uint16_t)((((STM32_PCLK1_FREQUENCY / 1000000) * 300) / 1000) + 1);
|
||||
|
||||
/* set our device address */
|
||||
rOAR1 = 0x1a << 1;
|
||||
|
||||
/* and enable the I2C port */
|
||||
rCR1 |= I2C_CR1_ACK | I2C_CR1_PE;
|
||||
}
|
||||
|
||||
static int
|
||||
i2c_interrupt(int irq, FAR void *context)
|
||||
{
|
||||
uint16_t sr1 = rSR1;
|
||||
|
||||
if (sr1 & (I2C_SR1_STOPF | I2C_SR1_AF | I2C_SR1_ADDR)) {
|
||||
|
||||
if (sr1 & I2C_SR1_STOPF) {
|
||||
/* write to CR1 to clear STOPF */
|
||||
(void)rSR1; /* as recommended, re-read SR1 */
|
||||
rCR1 |= I2C_CR1_PE;
|
||||
}
|
||||
|
||||
/* DMA never stops, so we should do that now */
|
||||
switch (direction) {
|
||||
case DIR_TX:
|
||||
i2c_tx_complete();
|
||||
break;
|
||||
case DIR_RX:
|
||||
i2c_rx_complete();
|
||||
break;
|
||||
default:
|
||||
/* not currently transferring - must be a new txn */
|
||||
break;
|
||||
}
|
||||
direction = DIR_NONE;
|
||||
}
|
||||
|
||||
if (sr1 & I2C_SR1_ADDR) {
|
||||
|
||||
/* clear ADDR to ack our selection and get direction */
|
||||
(void)rSR1; /* as recommended, re-read SR1 */
|
||||
uint16_t sr2 = rSR2;
|
||||
|
||||
if (sr2 & I2C_SR2_TRA) {
|
||||
/* we are the transmitter */
|
||||
|
||||
direction = DIR_TX;
|
||||
|
||||
} else {
|
||||
/* we are the receiver */
|
||||
|
||||
direction = DIR_RX;
|
||||
}
|
||||
}
|
||||
|
||||
/* clear any errors that might need it (this handles AF as well */
|
||||
if (sr1 & I2C_SR1_ERRORMASK)
|
||||
rSR1 = 0;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_rx_setup(void)
|
||||
{
|
||||
/*
|
||||
* Note that we configure DMA in circular mode; this means that a too-long
|
||||
* transfer will overwrite the buffer, but that avoids us having to deal with
|
||||
* bailing out of a transaction while the master is still babbling at us.
|
||||
*/
|
||||
rx_len = 0;
|
||||
stm32_dmasetup(rx_dma, (uintptr_t)&rDR, (uintptr_t)&rx_buf[0], sizeof(rx_buf),
|
||||
DMA_CCR_CIRC |
|
||||
DMA_CCR_MINC |
|
||||
DMA_CCR_PSIZE_32BITS |
|
||||
DMA_CCR_MSIZE_8BITS |
|
||||
DMA_CCR_PRIMED);
|
||||
|
||||
stm32_dmastart(rx_dma, NULL, NULL, false);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_rx_complete(void)
|
||||
{
|
||||
rx_len = sizeof(rx_buf) - stm32_dmaresidual(rx_dma);
|
||||
stm32_dmastop(rx_dma);
|
||||
|
||||
if (rx_len >= 2) {
|
||||
selected_page = rx_buf[0];
|
||||
selected_offset = rx_buf[1];
|
||||
|
||||
/* work out how many registers are being written */
|
||||
unsigned count = (rx_len - 2) / 2;
|
||||
if (count > 0) {
|
||||
registers_set(selected_page, selected_offset, (const uint16_t *)&rx_buf[2], count);
|
||||
} else {
|
||||
/* no registers written, must be an address cycle */
|
||||
uint16_t *regs;
|
||||
unsigned reg_count;
|
||||
|
||||
/* work out which registers are being addressed */
|
||||
int ret = registers_get(selected_page, selected_offset, ®s, ®_count);
|
||||
if (ret == 0) {
|
||||
tx_buf = (uint8_t *)regs;
|
||||
tx_len = reg_count * 2;
|
||||
} else {
|
||||
tx_buf = junk_buf;
|
||||
tx_len = sizeof(junk_buf);
|
||||
}
|
||||
|
||||
/* disable interrupts while reconfiguring DMA for the selected registers */
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
stm32_dmastop(tx_dma);
|
||||
i2c_tx_setup();
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
}
|
||||
|
||||
/* prepare for the next transaction */
|
||||
i2c_rx_setup();
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_tx_setup(void)
|
||||
{
|
||||
/*
|
||||
* Note that we configure DMA in circular mode; this means that a too-long
|
||||
* transfer will copy the buffer more than once, but that avoids us having
|
||||
* to deal with bailing out of a transaction while the master is still
|
||||
* babbling at us.
|
||||
*/
|
||||
stm32_dmasetup(tx_dma, (uintptr_t)&rDR, (uintptr_t)&tx_buf[0], tx_len,
|
||||
DMA_CCR_DIR |
|
||||
DMA_CCR_CIRC |
|
||||
DMA_CCR_MINC |
|
||||
DMA_CCR_PSIZE_8BITS |
|
||||
DMA_CCR_MSIZE_8BITS |
|
||||
DMA_CCR_PRIMED);
|
||||
|
||||
stm32_dmastart(tx_dma, NULL, NULL, false);
|
||||
}
|
||||
|
||||
static void
|
||||
i2c_tx_complete(void)
|
||||
{
|
||||
tx_count = tx_len - stm32_dmaresidual(tx_dma);
|
||||
stm32_dmastop(tx_dma);
|
||||
|
||||
/* for debug purposes, save the length of the last transmit as seen by the DMA */
|
||||
|
||||
/* leave tx_buf/tx_len alone, so that a retry will see the same data */
|
||||
|
||||
/* prepare for the next transaction */
|
||||
i2c_tx_setup();
|
||||
}
|
||||
|
||||
void
|
||||
i2c_dump(void)
|
||||
{
|
||||
debug("CR1 0x%08x CR2 0x%08x", rCR1, rCR2);
|
||||
debug("OAR1 0x%08x OAR2 0x%08x", rOAR1, rOAR2);
|
||||
debug("CCR 0x%08x TRISE 0x%08x", rCCR, rTRISE);
|
||||
debug("SR1 0x%08x SR2 0x%08x", rSR1, rSR2);
|
||||
}
|
|
@ -38,22 +38,14 @@
|
|||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <syslog.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sched.h>
|
||||
|
||||
#include <debug.h>
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
#include <systemlib/mixer/mixer.h>
|
||||
|
||||
|
@ -75,13 +67,16 @@ extern "C" {
|
|||
#define OVERRIDE 4
|
||||
|
||||
/* current servo arm/disarm state */
|
||||
bool mixer_servos_armed = false;
|
||||
static bool mixer_servos_armed = false;
|
||||
|
||||
/* selected control values and count for mixing */
|
||||
static uint16_t *control_values;
|
||||
static int control_count;
|
||||
|
||||
static uint16_t rc_channel_data[PX4IO_INPUT_CHANNELS];
|
||||
enum mixer_source {
|
||||
MIX_NONE,
|
||||
MIX_FMU,
|
||||
MIX_OVERRIDE,
|
||||
MIX_FAILSAFE
|
||||
};
|
||||
static mixer_source source;
|
||||
|
||||
static int mixer_callback(uintptr_t handle,
|
||||
uint8_t control_group,
|
||||
|
@ -93,87 +88,64 @@ static MixerGroup mixer_group(mixer_callback, 0);
|
|||
void
|
||||
mixer_tick(void)
|
||||
{
|
||||
bool should_arm;
|
||||
|
||||
/* check that we are receiving fresh data from the FMU */
|
||||
if ((hrt_absolute_time() - system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
|
||||
/* too many frames without FMU input, time to go to failsafe */
|
||||
system_state.mixer_manual_override = true;
|
||||
system_state.mixer_fmu_available = false;
|
||||
if (hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
|
||||
|
||||
/* too long without FMU input, time to go to failsafe */
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
|
||||
lowsyslog("AP RX timeout");
|
||||
}
|
||||
r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM);
|
||||
r_status_alarms |= PX4IO_P_STATUS_ALARMS_FMU_LOST;
|
||||
|
||||
/* XXX this is questionable - vehicle may not make sense for direct control */
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE;
|
||||
} else {
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
|
||||
r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_FMU_LOST;
|
||||
}
|
||||
|
||||
source = MIX_FAILSAFE;
|
||||
|
||||
/*
|
||||
* Decide which set of inputs we're using.
|
||||
* Decide which set of controls we're using.
|
||||
*/
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ||
|
||||
!(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
|
||||
/* this is for planes, where manual override makes sense */
|
||||
if (system_state.manual_override_ok) {
|
||||
/* if everything is ok */
|
||||
if (!system_state.mixer_manual_override && system_state.mixer_fmu_available) {
|
||||
/* we have recent control data from the FMU */
|
||||
control_count = PX4IO_CONTROL_CHANNELS;
|
||||
control_values = &system_state.fmu_channel_data[0];
|
||||
/* don't actually mix anything - we already have raw PWM values or
|
||||
not a valid mixer. */
|
||||
source = MIX_NONE;
|
||||
|
||||
} else if (system_state.rc_channels > 0) {
|
||||
/* when override is on or the fmu is not available, but RC is present */
|
||||
control_count = system_state.rc_channels;
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* remap roll, pitch, yaw and throttle from RC specific to internal ordering */
|
||||
rc_channel_data[ROLL] = system_state.rc_channel_data[system_state.rc_map[ROLL] - 1];
|
||||
rc_channel_data[PITCH] = system_state.rc_channel_data[system_state.rc_map[PITCH] - 1];
|
||||
rc_channel_data[YAW] = system_state.rc_channel_data[system_state.rc_map[YAW] - 1];
|
||||
rc_channel_data[THROTTLE] = system_state.rc_channel_data[system_state.rc_map[THROTTLE] - 1];
|
||||
//rc_channel_data[OVERRIDE] = system_state.rc_channel_data[system_state.rc_map[OVERRIDE] - 1];
|
||||
|
||||
/* get the remaining channels, no remapping needed */
|
||||
for (unsigned i = 4; i < system_state.rc_channels; i++) {
|
||||
rc_channel_data[i] = system_state.rc_channel_data[i];
|
||||
}
|
||||
|
||||
/* scale the control inputs */
|
||||
rc_channel_data[THROTTLE] = ((float)(rc_channel_data[THROTTLE] - system_state.rc_min[THROTTLE]) /
|
||||
(float)(system_state.rc_max[THROTTLE] - system_state.rc_min[THROTTLE])) * 1000.0f + 1000;
|
||||
|
||||
if (rc_channel_data[THROTTLE] > 2000) {
|
||||
rc_channel_data[THROTTLE] = 2000;
|
||||
}
|
||||
|
||||
if (rc_channel_data[THROTTLE] < 1000) {
|
||||
rc_channel_data[THROTTLE] = 1000;
|
||||
}
|
||||
|
||||
// lowsyslog("Tmin: %d Ttrim: %d Tmax: %d T: %d \n",
|
||||
// (int)(system_state.rc_min[THROTTLE]), (int)(system_state.rc_trim[THROTTLE]),
|
||||
// (int)(system_state.rc_max[THROTTLE]), (int)(rc_channel_data[THROTTLE]));
|
||||
|
||||
control_values = &rc_channel_data[0];
|
||||
sched_unlock();
|
||||
} else {
|
||||
/* we have no control input (no FMU, no RC) */
|
||||
|
||||
// XXX builtin failsafe would activate here
|
||||
control_count = 0;
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
|
||||
/* mix from FMU controls */
|
||||
source = MIX_FMU;
|
||||
}
|
||||
//lowsyslog("R: %d P: %d Y: %d T: %d \n", control_values[0], control_values[1], control_values[2], control_values[3]);
|
||||
|
||||
/* this is for multicopters, etc. where manual override does not make sense */
|
||||
} else {
|
||||
/* if the fmu is available whe are good */
|
||||
if (system_state.mixer_fmu_available) {
|
||||
control_count = PX4IO_CONTROL_CHANNELS;
|
||||
control_values = &system_state.fmu_channel_data[0];
|
||||
/* we better shut everything off */
|
||||
} else {
|
||||
control_count = 0;
|
||||
if ( (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
|
||||
|
||||
/* if allowed, mix from RC inputs directly */
|
||||
source = MIX_OVERRIDE;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Run the mixers if we have any control data at all.
|
||||
* Run the mixers.
|
||||
*/
|
||||
if (control_count > 0) {
|
||||
if (source == MIX_FAILSAFE) {
|
||||
|
||||
/* copy failsafe values to the servo outputs */
|
||||
for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
|
||||
r_page_servos[i] = r_page_servo_failsafe[i];
|
||||
|
||||
} else if (source != MIX_NONE) {
|
||||
|
||||
float outputs[IO_SERVO_COUNT];
|
||||
unsigned mixed;
|
||||
|
||||
|
@ -181,31 +153,33 @@ mixer_tick(void)
|
|||
mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT);
|
||||
|
||||
/* scale to PWM and update the servo outputs as required */
|
||||
for (unsigned i = 0; i < IO_SERVO_COUNT; i++) {
|
||||
if (i < mixed) {
|
||||
for (unsigned i = 0; i < mixed; i++) {
|
||||
|
||||
/* save actuator values for FMU readback */
|
||||
r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
|
||||
|
||||
/* scale to servo output */
|
||||
system_state.servos[i] = (outputs[i] * 500.0f) + 1500;
|
||||
r_page_servos[i] = (outputs[i] * 500.0f) + 1500;
|
||||
|
||||
} else {
|
||||
/* set to zero to inhibit PWM pulse output */
|
||||
system_state.servos[i] = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* If we are armed, update the servo output.
|
||||
*/
|
||||
if (system_state.armed && system_state.arm_ok) {
|
||||
up_pwm_servo_set(i, system_state.servos[i]);
|
||||
}
|
||||
}
|
||||
for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
|
||||
r_page_servos[i] = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* Decide whether the servos should be armed right now.
|
||||
* A sufficient reason is armed state and either FMU or RC control inputs
|
||||
*
|
||||
* We must be armed, and we must have a PWM source; either raw from
|
||||
* FMU or from the mixer.
|
||||
*
|
||||
* XXX correct behaviour for failsafe may require an additional case
|
||||
* here.
|
||||
*/
|
||||
|
||||
should_arm = system_state.armed && system_state.arm_ok && (control_count > 0);
|
||||
bool should_arm = (
|
||||
/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) &&
|
||||
/* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
|
||||
/* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
|
||||
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK));
|
||||
|
||||
if (should_arm && !mixer_servos_armed) {
|
||||
/* need to arm, but not armed */
|
||||
|
@ -217,6 +191,12 @@ mixer_tick(void)
|
|||
up_pwm_servo_arm(false);
|
||||
mixer_servos_armed = false;
|
||||
}
|
||||
|
||||
if (mixer_servos_armed) {
|
||||
/* update the servo outputs. */
|
||||
for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
|
||||
up_pwm_servo_set(i, r_page_servos[i]);
|
||||
}
|
||||
}
|
||||
|
||||
static int
|
||||
|
@ -225,30 +205,54 @@ mixer_callback(uintptr_t handle,
|
|||
uint8_t control_index,
|
||||
float &control)
|
||||
{
|
||||
/* if the control index refers to an input that's not valid, we can't return it */
|
||||
if (control_index >= control_count)
|
||||
if (control_group != 0)
|
||||
return -1;
|
||||
|
||||
/* scale from current PWM units (1000-2000) to mixer input values */
|
||||
if (system_state.manual_override_ok && system_state.mixer_manual_override && control_index == 3) {
|
||||
control = ((float)control_values[control_index] - 1000.0f) / 1000.0f;
|
||||
} else {
|
||||
control = ((float)control_values[control_index] - 1500.0f) / 500.0f;
|
||||
switch (source) {
|
||||
case MIX_FMU:
|
||||
if (control_index < PX4IO_CONTROL_CHANNELS) {
|
||||
control = REG_TO_FLOAT(r_page_controls[control_index]);
|
||||
break;
|
||||
}
|
||||
return -1;
|
||||
|
||||
case MIX_OVERRIDE:
|
||||
if (r_page_rc_input[PX4IO_P_RC_VALID] & (1 << control_index)) {
|
||||
control = REG_TO_FLOAT(r_page_rc_input[PX4IO_P_RC_BASE + control_index]);
|
||||
break;
|
||||
}
|
||||
return -1;
|
||||
|
||||
case MIX_FAILSAFE:
|
||||
case MIX_NONE:
|
||||
/* XXX we could allow for configuration of per-output failsafe values */
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static char mixer_text[256];
|
||||
/*
|
||||
* XXX error handling here should be more aggressive; currently it is
|
||||
* possible to get STATUS_FLAGS_MIXER_OK set even though the mixer has
|
||||
* not loaded faithfully.
|
||||
*/
|
||||
|
||||
static char mixer_text[256]; /* large enough for one mixer */
|
||||
static unsigned mixer_text_length = 0;
|
||||
|
||||
void
|
||||
mixer_handle_text(const void *buffer, size_t length)
|
||||
{
|
||||
/* do not allow a mixer change while fully armed */
|
||||
if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) &&
|
||||
/* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
|
||||
return;
|
||||
}
|
||||
|
||||
px4io_mixdata *msg = (px4io_mixdata *)buffer;
|
||||
|
||||
debug("mixer text %u", length);
|
||||
isr_debug(2, "mix txt %u", length);
|
||||
|
||||
if (length < sizeof(px4io_mixdata))
|
||||
return;
|
||||
|
@ -257,23 +261,30 @@ mixer_handle_text(const void *buffer, size_t length)
|
|||
|
||||
switch (msg->action) {
|
||||
case F2I_MIXER_ACTION_RESET:
|
||||
debug("reset");
|
||||
isr_debug(2, "reset");
|
||||
|
||||
/* FIRST mark the mixer as invalid */
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
/* THEN actually delete it */
|
||||
mixer_group.reset();
|
||||
mixer_text_length = 0;
|
||||
|
||||
/* FALLTHROUGH */
|
||||
case F2I_MIXER_ACTION_APPEND:
|
||||
debug("append %d", length);
|
||||
isr_debug(2, "append %d", length);
|
||||
|
||||
/* check for overflow - this is really fatal */
|
||||
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text))
|
||||
/* XXX could add just what will fit & try to parse, then repeat... */
|
||||
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
return;
|
||||
}
|
||||
|
||||
/* append mixer text and nul-terminate */
|
||||
memcpy(&mixer_text[mixer_text_length], msg->text, text_length);
|
||||
mixer_text_length += text_length;
|
||||
mixer_text[mixer_text_length] = '\0';
|
||||
debug("buflen %u", mixer_text_length);
|
||||
isr_debug(2, "buflen %u", mixer_text_length);
|
||||
|
||||
/* process the text buffer, adding new mixers as their descriptions can be parsed */
|
||||
unsigned resid = mixer_text_length;
|
||||
|
@ -281,7 +292,11 @@ mixer_handle_text(const void *buffer, size_t length)
|
|||
|
||||
/* if anything was parsed */
|
||||
if (resid != mixer_text_length) {
|
||||
debug("used %u", mixer_text_length - resid);
|
||||
|
||||
/* ideally, this should test resid == 0 ? */
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
|
||||
isr_debug(2, "used %u", mixer_text_length - resid);
|
||||
|
||||
/* copy any leftover text to the base of the buffer for re-use */
|
||||
if (resid > 0)
|
||||
|
|
|
@ -31,67 +31,152 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file PX4FMU <-> PX4IO messaging protocol.
|
||||
*
|
||||
* This initial version of the protocol is very simple; each side transmits a
|
||||
* complete update with each frame. This avoids the sending of many small
|
||||
* messages and the corresponding complexity involved.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file protocol.h
|
||||
*
|
||||
* PX4IO I2C interface protocol.
|
||||
*
|
||||
* Communication is performed via writes to and reads from 16-bit virtual
|
||||
* registers organised into pages of 255 registers each.
|
||||
*
|
||||
* The first two bytes of each write select a page and offset address
|
||||
* respectively. Subsequent reads and writes increment the offset within
|
||||
* the page.
|
||||
*
|
||||
* Most pages are readable or writable but not both.
|
||||
*
|
||||
* Note that some pages may permit offset values greater than 255, which
|
||||
* can only be achieved by long writes. The offset does not wrap.
|
||||
*
|
||||
* Writes to unimplemented registers are ignored. Reads from unimplemented
|
||||
* registers return undefined values.
|
||||
*
|
||||
* As convention, values that would be floating point in other parts of
|
||||
* the PX4 system are expressed as signed integer values scaled by 10000,
|
||||
* e.g. control values range from -10000..10000. Use the REG_TO_SIGNED and
|
||||
* SIGNED_TO_REG macros to convert between register representation and
|
||||
* the signed version, and REG_TO_FLOAT/FLOAT_TO_REG to convert to float.
|
||||
*
|
||||
* Note that the implementation of readable pages prefers registers within
|
||||
* readable pages to be densely packed. Page numbers do not need to be
|
||||
* packed.
|
||||
*/
|
||||
|
||||
#define PX4IO_CONTROL_CHANNELS 8
|
||||
#define PX4IO_INPUT_CHANNELS 12
|
||||
#define PX4IO_RELAY_CHANNELS 4
|
||||
|
||||
#pragma pack(push, 1)
|
||||
/* Per C, this is safe for all 2's complement systems */
|
||||
#define REG_TO_SIGNED(_reg) ((int16_t)(_reg))
|
||||
#define SIGNED_TO_REG(_signed) ((uint16_t)(_signed))
|
||||
|
||||
/**
|
||||
* Periodic command from FMU to IO.
|
||||
*/
|
||||
struct px4io_command {
|
||||
uint16_t f2i_magic;
|
||||
#define F2I_MAGIC 0x636d
|
||||
#define REG_TO_FLOAT(_reg) ((float)REG_TO_SIGNED(_reg) / 10000.0f)
|
||||
#define FLOAT_TO_REG(_float) SIGNED_TO_REG((int16_t)((_float) * 10000.0f))
|
||||
|
||||
uint16_t servo_rate;
|
||||
uint16_t output_control[PX4IO_CONTROL_CHANNELS]; /**< PWM output rate in Hz */
|
||||
bool relay_state[PX4IO_RELAY_CHANNELS]; /**< relay states as requested by FMU */
|
||||
bool arm_ok; /**< FMU allows full arming */
|
||||
bool vector_flight_mode_ok; /**< FMU aquired a valid position lock, ready for pos control */
|
||||
bool manual_override_ok; /**< if true, IO performs a direct manual override */
|
||||
};
|
||||
/* static configuration page */
|
||||
#define PX4IO_PAGE_CONFIG 0
|
||||
#define PX4IO_P_CONFIG_PROTOCOL_VERSION 0 /* magic numbers TBD */
|
||||
#define PX4IO_P_CONFIG_SOFTWARE_VERSION 1 /* magic numbers TBD */
|
||||
#define PX4IO_P_CONFIG_BOOTLOADER_VERSION 2 /* get this how? */
|
||||
#define PX4IO_P_CONFIG_MAX_TRANSFER 3 /* maximum I2C transfer size */
|
||||
#define PX4IO_P_CONFIG_CONTROL_COUNT 4 /* hardcoded max control count supported */
|
||||
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
|
||||
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
|
||||
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
|
||||
#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* harcoded # of relay outputs */
|
||||
|
||||
/**
|
||||
* Periodic report from IO to FMU
|
||||
*/
|
||||
struct px4io_report {
|
||||
uint16_t i2f_magic;
|
||||
#define I2F_MAGIC 0x7570
|
||||
/* dynamic status page */
|
||||
#define PX4IO_PAGE_STATUS 1
|
||||
#define PX4IO_P_STATUS_FREEMEM 0
|
||||
#define PX4IO_P_STATUS_CPULOAD 1
|
||||
|
||||
uint16_t rc_channel[PX4IO_INPUT_CHANNELS];
|
||||
bool armed;
|
||||
uint8_t channel_count;
|
||||
#define PX4IO_P_STATUS_FLAGS 2 /* monitoring flags */
|
||||
#define PX4IO_P_STATUS_FLAGS_ARMED (1 << 0) /* arm-ok and locally armed */
|
||||
#define PX4IO_P_STATUS_FLAGS_OVERRIDE (1 << 1) /* in manual override */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_OK (1 << 2) /* RC input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_PPM (1 << 3) /* PPM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_DSM (1 << 4) /* DSM input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RC_SBUS (1 << 5) /* SBUS input is valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_FMU_OK (1 << 6) /* controls from FMU are valid */
|
||||
#define PX4IO_P_STATUS_FLAGS_RAW_PWM (1 << 7) /* raw PWM from FMU is bypassing the mixer */
|
||||
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
|
||||
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
|
||||
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
|
||||
|
||||
uint16_t battery_mv;
|
||||
uint16_t adc_in;
|
||||
uint8_t overcurrent;
|
||||
};
|
||||
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
|
||||
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */
|
||||
#define PX4IO_P_STATUS_ALARMS_TEMPERATURE (1 << 1) /* board temperature is high */
|
||||
#define PX4IO_P_STATUS_ALARMS_SERVO_CURRENT (1 << 2) /* servo current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_ACC_CURRENT (1 << 3) /* accessory current limit was exceeded */
|
||||
#define PX4IO_P_STATUS_ALARMS_FMU_LOST (1 << 4) /* timed out waiting for controls from FMU */
|
||||
#define PX4IO_P_STATUS_ALARMS_RC_LOST (1 << 5) /* timed out waiting for RC input */
|
||||
|
||||
/**
|
||||
* As-needed config message from FMU to IO
|
||||
*/
|
||||
struct px4io_config {
|
||||
uint16_t f2i_config_magic;
|
||||
#define F2I_CONFIG_MAGIC 0x6366
|
||||
#define PX4IO_P_STATUS_VBATT 4 /* battery voltage in mV */
|
||||
#define PX4IO_P_STATUS_IBATT 5 /* battery current in cA */
|
||||
|
||||
uint8_t rc_map[4]; /**< channel ordering of roll, pitch, yaw, throttle */
|
||||
uint16_t rc_min[4]; /**< min value for each channel */
|
||||
uint16_t rc_trim[4]; /**< trim value for each channel */
|
||||
uint16_t rc_max[4]; /**< max value for each channel */
|
||||
int8_t rc_rev[4]; /**< rev value for each channel */
|
||||
uint16_t rc_dz[4]; /**< dz value for each channel */
|
||||
};
|
||||
/* array of post-mix actuator outputs, -10000..10000 */
|
||||
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of PWM servo output values, microseconds */
|
||||
#define PX4IO_PAGE_SERVOS 3 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* array of raw RC input values, microseconds */
|
||||
#define PX4IO_PAGE_RAW_RC_INPUT 4
|
||||
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */
|
||||
#define PX4IO_P_RAW_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT channels from here */
|
||||
|
||||
/* array of scaled RC input values, -10000..10000 */
|
||||
#define PX4IO_PAGE_RC_INPUT 5
|
||||
#define PX4IO_P_RC_VALID 0 /* bitmask of valid controls */
|
||||
#define PX4IO_P_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT controls from here */
|
||||
|
||||
/* array of raw ADC values */
|
||||
#define PX4IO_PAGE_RAW_ADC_INPUT 6 /* 0..CONFIG_ADC_INPUT_COUNT-1 */
|
||||
|
||||
/* setup page */
|
||||
#define PX4IO_PAGE_SETUP 100
|
||||
#define PX4IO_P_SETUP_FEATURES 0
|
||||
|
||||
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
|
||||
#define PX4IO_P_SETUP_ARMING_ARM_OK (1 << 0) /* OK to arm */
|
||||
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
|
||||
#define PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK (1 << 3) /* OK to perform position / vector control (= position lock) */
|
||||
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
|
||||
|
||||
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
|
||||
#define PX4IO_P_SETUP_PWM_LOWRATE 3 /* 'low' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_PWM_HIGHRATE 4 /* 'high' PWM frame output rate in Hz */
|
||||
#define PX4IO_P_SETUP_RELAYS 5 /* bitmask of relay/switch outputs, 0 = off, 1 = on */
|
||||
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* battery voltage correction factor (float) */
|
||||
#define PX4IO_P_SETUP_IBATT_SCALE 7 /* battery current scaling factor (float) */
|
||||
#define PX4IO_P_SETUP_IBATT_BIAS 8 /* battery current bias value */
|
||||
#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
|
||||
|
||||
/* autopilot control values, -10000..10000 */
|
||||
#define PX4IO_PAGE_CONTROLS 101 /* 0..CONFIG_CONTROL_COUNT */
|
||||
|
||||
/* raw text load to the mixer parser - ignores offset */
|
||||
#define PX4IO_PAGE_MIXERLOAD 102
|
||||
|
||||
/* R/C channel config */
|
||||
#define PX4IO_PAGE_RC_CONFIG 103 /* R/C input configuration */
|
||||
#define PX4IO_P_RC_CONFIG_MIN 0 /* lowest input value */
|
||||
#define PX4IO_P_RC_CONFIG_CENTER 1 /* center input value */
|
||||
#define PX4IO_P_RC_CONFIG_MAX 2 /* highest input value */
|
||||
#define PX4IO_P_RC_CONFIG_DEADZONE 3 /* band around center that is ignored */
|
||||
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /* mapped input value */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS 5 /* channel options bitmask */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
|
||||
#define PX4IO_P_RC_CONFIG_STRIDE 6 /* spacing between channel config data */
|
||||
|
||||
/* PWM output - overrides mixer */
|
||||
#define PX4IO_PAGE_DIRECT_PWM 104 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/* PWM failsafe values - zero disables the output */
|
||||
#define PX4IO_PAGE_FAILSAFE_PWM 105 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||
|
||||
/**
|
||||
* As-needed mixer data upload.
|
||||
|
@ -99,6 +184,7 @@ struct px4io_config {
|
|||
* This message adds text to the mixer text buffer; the text
|
||||
* buffer is drained as the definitions are consumed.
|
||||
*/
|
||||
#pragma pack(push, 1)
|
||||
struct px4io_mixdata {
|
||||
uint16_t f2i_mixer_magic;
|
||||
#define F2I_MIXER_MAGIC 0x6d74
|
||||
|
@ -109,8 +195,5 @@ struct px4io_mixdata {
|
|||
|
||||
char text[0]; /* actual text size may vary */
|
||||
};
|
||||
|
||||
/* maximum size is limited by the HX frame size */
|
||||
#define F2I_MIXER_MAX_TEXT (HX_STREAM_MAX_FRAME - sizeof(struct px4io_mixdata))
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
|
|
|
@ -37,20 +37,23 @@
|
|||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <stdio.h> // required for task_create
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <debug.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <nuttx/clock.h>
|
||||
#include <poll.h>
|
||||
#include <signal.h>
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#define DEBUG
|
||||
#include "px4io.h"
|
||||
|
||||
__EXPORT int user_start(int argc, char *argv[]);
|
||||
|
@ -59,19 +62,79 @@ extern void up_cxxinitialize(void);
|
|||
|
||||
struct sys_state_s system_state;
|
||||
|
||||
int user_start(int argc, char *argv[])
|
||||
static struct hrt_call serial_dma_call;
|
||||
|
||||
/* store i2c reset count XXX this should be a register, together with other error counters */
|
||||
volatile uint32_t i2c_loop_resets = 0;
|
||||
|
||||
/*
|
||||
* a set of debug buffers to allow us to send debug information from ISRs
|
||||
*/
|
||||
|
||||
static volatile uint32_t msg_counter;
|
||||
static volatile uint32_t last_msg_counter;
|
||||
static volatile uint8_t msg_next_out, msg_next_in;
|
||||
|
||||
/*
|
||||
* WARNING: too large buffers here consume the memory required
|
||||
* for mixer handling. Do not allocate more than 80 bytes for
|
||||
* output.
|
||||
*/
|
||||
#define NUM_MSG 2
|
||||
static char msg[NUM_MSG][40];
|
||||
|
||||
/*
|
||||
* add a debug message to be printed on the console
|
||||
*/
|
||||
void
|
||||
isr_debug(uint8_t level, const char *fmt, ...)
|
||||
{
|
||||
if (level > r_page_setup[PX4IO_P_SETUP_SET_DEBUG]) {
|
||||
return;
|
||||
}
|
||||
va_list ap;
|
||||
va_start(ap, fmt);
|
||||
vsnprintf(msg[msg_next_in], sizeof(msg[0]), fmt, ap);
|
||||
va_end(ap);
|
||||
msg_next_in = (msg_next_in+1) % NUM_MSG;
|
||||
msg_counter++;
|
||||
}
|
||||
|
||||
/*
|
||||
* show all pending debug messages
|
||||
*/
|
||||
static void
|
||||
show_debug_messages(void)
|
||||
{
|
||||
if (msg_counter != last_msg_counter) {
|
||||
uint32_t n = msg_counter - last_msg_counter;
|
||||
if (n > NUM_MSG) n = NUM_MSG;
|
||||
last_msg_counter = msg_counter;
|
||||
while (n--) {
|
||||
debug("%s", msg[msg_next_out]);
|
||||
msg_next_out = (msg_next_out+1) % NUM_MSG;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
user_start(int argc, char *argv[])
|
||||
{
|
||||
/* run C++ ctors before we go any further */
|
||||
up_cxxinitialize();
|
||||
|
||||
/* reset all to zero */
|
||||
memset(&system_state, 0, sizeof(system_state));
|
||||
/* default to 50 Hz PWM outputs */
|
||||
system_state.servo_rate = 50;
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
|
||||
|
||||
/* print some startup info */
|
||||
lowsyslog("\nPX4IO: starting\n");
|
||||
|
||||
|
@ -89,17 +152,80 @@ int user_start(int argc, char *argv[])
|
|||
/* configure the first 8 PWM outputs (i.e. all of them) */
|
||||
up_pwm_servo_init(0xff);
|
||||
|
||||
/* start the flight control signal handler */
|
||||
task_create("FCon",
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
1024,
|
||||
(main_t)controls_main,
|
||||
NULL);
|
||||
/* initialise the control inputs */
|
||||
controls_init();
|
||||
|
||||
/* start the i2c handler */
|
||||
i2c_init();
|
||||
|
||||
/* add a performance counter for mixing */
|
||||
perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix");
|
||||
|
||||
/* add a performance counter for controls */
|
||||
perf_counter_t controls_perf = perf_alloc(PC_ELAPSED, "controls");
|
||||
|
||||
/* and one for measuring the loop rate */
|
||||
perf_counter_t loop_perf = perf_alloc(PC_INTERVAL, "loop");
|
||||
|
||||
struct mallinfo minfo = mallinfo();
|
||||
lowsyslog("free %u largest %u\n", minfo.mxordblk, minfo.fordblks);
|
||||
lowsyslog("MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks);
|
||||
|
||||
/* we're done here, go run the communications loop */
|
||||
comms_main();
|
||||
#if 0
|
||||
/* not enough memory, lock down */
|
||||
if (minfo.mxordblk < 500) {
|
||||
lowsyslog("ERR: not enough MEM");
|
||||
bool phase = false;
|
||||
|
||||
if (phase) {
|
||||
LED_AMBER(true);
|
||||
LED_BLUE(false);
|
||||
} else {
|
||||
LED_AMBER(false);
|
||||
LED_BLUE(true);
|
||||
}
|
||||
|
||||
phase = !phase;
|
||||
usleep(300000);
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Run everything in a tight loop.
|
||||
*/
|
||||
|
||||
uint64_t last_debug_time = 0;
|
||||
for (;;) {
|
||||
|
||||
/* track the rate at which the loop is running */
|
||||
perf_count(loop_perf);
|
||||
|
||||
/* kick the mixer */
|
||||
perf_begin(mixer_perf);
|
||||
mixer_tick();
|
||||
perf_end(mixer_perf);
|
||||
|
||||
/* kick the control inputs */
|
||||
perf_begin(controls_perf);
|
||||
controls_tick();
|
||||
perf_end(controls_perf);
|
||||
|
||||
/* check for debug activity */
|
||||
show_debug_messages();
|
||||
|
||||
/* post debug state at ~1Hz */
|
||||
if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) {
|
||||
|
||||
struct mallinfo minfo = mallinfo();
|
||||
|
||||
isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x r=%u m=%u",
|
||||
(unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG],
|
||||
(unsigned)r_status_flags,
|
||||
(unsigned)r_setup_arming,
|
||||
(unsigned)r_setup_features,
|
||||
(unsigned)i2c_loop_resets,
|
||||
(unsigned)minfo.mxordblk);
|
||||
last_debug_time = hrt_absolute_time();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -63,130 +63,59 @@
|
|||
# define debug(fmt, args...) do {} while(0)
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Registers.
|
||||
*/
|
||||
extern uint16_t r_page_status[]; /* PX4IO_PAGE_STATUS */
|
||||
extern uint16_t r_page_actuators[]; /* PX4IO_PAGE_ACTUATORS */
|
||||
extern uint16_t r_page_servos[]; /* PX4IO_PAGE_SERVOS */
|
||||
extern uint16_t r_page_raw_rc_input[]; /* PX4IO_PAGE_RAW_RC_INPUT */
|
||||
extern uint16_t r_page_rc_input[]; /* PX4IO_PAGE_RC_INPUT */
|
||||
extern uint16_t r_page_adc[]; /* PX4IO_PAGE_RAW_ADC_INPUT */
|
||||
|
||||
extern volatile uint16_t r_page_setup[]; /* PX4IO_PAGE_SETUP */
|
||||
extern volatile uint16_t r_page_controls[]; /* PX4IO_PAGE_CONTROLS */
|
||||
extern uint16_t r_page_rc_input_config[]; /* PX4IO_PAGE_RC_INPUT_CONFIG */
|
||||
extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
|
||||
|
||||
/*
|
||||
* Register aliases.
|
||||
*
|
||||
* Handy aliases for registers that are widely used.
|
||||
*/
|
||||
#define r_status_flags r_page_status[PX4IO_P_STATUS_FLAGS]
|
||||
#define r_status_alarms r_page_status[PX4IO_P_STATUS_ALARMS]
|
||||
|
||||
#define r_raw_rc_count r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT]
|
||||
#define r_raw_rc_values (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE])
|
||||
#define r_rc_valid r_page_rc_input[PX4IO_P_RC_VALID]
|
||||
#define r_rc_values (&r_page_rc_input[PX4IO_P_RAW_RC_BASE])
|
||||
|
||||
#define r_setup_features r_page_setup[PX4IO_P_SETUP_FEATURES]
|
||||
#define r_setup_arming r_page_setup[PX4IO_P_SETUP_ARMING]
|
||||
#define r_setup_pwm_rates r_page_setup[PX4IO_P_SETUP_PWM_RATES]
|
||||
#define r_setup_pwm_lowrate r_page_setup[PX4IO_P_SETUP_PWM_LOWRATE]
|
||||
#define r_setup_pwm_highrate r_page_setup[PX4IO_P_SETUP_PWM_HIGHRATE]
|
||||
#define r_setup_relays r_page_setup[PX4IO_P_SETUP_RELAYS]
|
||||
|
||||
#define r_control_values (&r_page_controls[0])
|
||||
|
||||
/*
|
||||
* System state structure.
|
||||
*/
|
||||
struct sys_state_s {
|
||||
|
||||
bool armed; /* IO armed */
|
||||
bool arm_ok; /* FMU says OK to arm */
|
||||
uint16_t servo_rate; /* output rate of servos in Hz */
|
||||
|
||||
/**
|
||||
* Remote control input(s) channel mappings
|
||||
*/
|
||||
uint8_t rc_map[4];
|
||||
|
||||
/**
|
||||
* Remote control channel attributes
|
||||
*/
|
||||
uint16_t rc_min[4];
|
||||
uint16_t rc_trim[4];
|
||||
uint16_t rc_max[4];
|
||||
int16_t rc_rev[4];
|
||||
uint16_t rc_dz[4];
|
||||
|
||||
/**
|
||||
* Data from the remote control input(s)
|
||||
*/
|
||||
unsigned rc_channels;
|
||||
uint16_t rc_channel_data[PX4IO_INPUT_CHANNELS];
|
||||
uint64_t rc_channels_timestamp;
|
||||
|
||||
/**
|
||||
* Control signals from FMU.
|
||||
*/
|
||||
uint16_t fmu_channel_data[PX4IO_CONTROL_CHANNELS];
|
||||
|
||||
/**
|
||||
* Mixed servo outputs
|
||||
*/
|
||||
uint16_t servos[IO_SERVO_COUNT];
|
||||
|
||||
/**
|
||||
* Relay controls
|
||||
*/
|
||||
bool relays[PX4IO_RELAY_CHANNELS];
|
||||
|
||||
/**
|
||||
* If true, we are using the FMU controls, else RC input if available.
|
||||
*/
|
||||
bool mixer_manual_override;
|
||||
|
||||
/**
|
||||
* If true, FMU input is available.
|
||||
*/
|
||||
bool mixer_fmu_available;
|
||||
|
||||
/**
|
||||
* If true, state that should be reported to FMU has been updated.
|
||||
*/
|
||||
bool fmu_report_due;
|
||||
volatile uint64_t rc_channels_timestamp;
|
||||
|
||||
/**
|
||||
* Last FMU receive time, in microseconds since system boot
|
||||
*/
|
||||
uint64_t fmu_data_received_time;
|
||||
|
||||
/**
|
||||
* Current serial interface mode, per the serial_rx_mode parameter
|
||||
* in the config packet.
|
||||
*/
|
||||
uint8_t serial_rx_mode;
|
||||
|
||||
/**
|
||||
* If true, the RC signal has been lost for more than a timeout interval
|
||||
*/
|
||||
bool rc_lost;
|
||||
|
||||
/**
|
||||
* If true, the connection to FMU has been lost for more than a timeout interval
|
||||
*/
|
||||
bool fmu_lost;
|
||||
|
||||
/**
|
||||
* If true, FMU is ready for autonomous position control. Only used for LED indication
|
||||
*/
|
||||
bool vector_flight_mode_ok;
|
||||
|
||||
/**
|
||||
* If true, IO performs an on-board manual override with the RC channel values
|
||||
*/
|
||||
bool manual_override_ok;
|
||||
|
||||
/*
|
||||
* Measured battery voltage in mV
|
||||
*/
|
||||
uint16_t battery_mv;
|
||||
|
||||
/*
|
||||
* ADC IN5 measurement
|
||||
*/
|
||||
uint16_t adc_in5;
|
||||
|
||||
/*
|
||||
* Power supply overcurrent status bits.
|
||||
*/
|
||||
uint8_t overcurrent;
|
||||
volatile uint64_t fmu_data_received_time;
|
||||
|
||||
};
|
||||
|
||||
extern struct sys_state_s system_state;
|
||||
|
||||
#if 0
|
||||
/*
|
||||
* Software countdown timers.
|
||||
*
|
||||
* Each timer counts down to zero at one tick per ms.
|
||||
*/
|
||||
#define TIMER_BLINK_AMBER 0
|
||||
#define TIMER_BLINK_BLUE 1
|
||||
#define TIMER_STATUS_PRINT 2
|
||||
#define TIMER_SANITY 7
|
||||
#define TIMER_NUM_TIMERS 8
|
||||
extern volatile int timers[TIMER_NUM_TIMERS];
|
||||
#endif
|
||||
|
||||
/*
|
||||
* GPIO handling.
|
||||
*/
|
||||
|
@ -206,6 +135,7 @@ extern volatile int timers[TIMER_NUM_TIMERS];
|
|||
|
||||
#define ADC_VBATT 4
|
||||
#define ADC_IN5 5
|
||||
#define ADC_CHANNEL_COUNT 2
|
||||
|
||||
/*
|
||||
* Mixer
|
||||
|
@ -213,34 +143,46 @@ extern volatile int timers[TIMER_NUM_TIMERS];
|
|||
extern void mixer_tick(void);
|
||||
extern void mixer_handle_text(const void *buffer, size_t length);
|
||||
|
||||
/*
|
||||
/**
|
||||
* Safety switch/LED.
|
||||
*/
|
||||
extern void safety_init(void);
|
||||
|
||||
/*
|
||||
/**
|
||||
* FMU communications
|
||||
*/
|
||||
extern void comms_main(void) __attribute__((noreturn));
|
||||
extern void i2c_init(void);
|
||||
|
||||
/*
|
||||
/**
|
||||
* Register space
|
||||
*/
|
||||
extern void registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
|
||||
extern int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values);
|
||||
|
||||
/**
|
||||
* Sensors/misc inputs
|
||||
*/
|
||||
extern int adc_init(void);
|
||||
extern uint16_t adc_measure(unsigned channel);
|
||||
|
||||
/*
|
||||
/**
|
||||
* R/C receiver handling.
|
||||
*
|
||||
* Input functions return true when they receive an update from the RC controller.
|
||||
*/
|
||||
extern void controls_main(void);
|
||||
extern void controls_init(void);
|
||||
extern void controls_tick(void);
|
||||
extern int dsm_init(const char *device);
|
||||
extern bool dsm_input(void);
|
||||
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
|
||||
extern int sbus_init(const char *device);
|
||||
extern bool sbus_input(void);
|
||||
extern bool sbus_input(uint16_t *values, uint16_t *num_values);
|
||||
|
||||
/** global debug level for isr_debug() */
|
||||
extern volatile uint8_t debug_level;
|
||||
|
||||
/* send a debug message to the console */
|
||||
extern void isr_debug(uint8_t level, const char *fmt, ...);
|
||||
|
||||
void i2c_dump(void);
|
||||
void i2c_reset(void);
|
||||
|
||||
/*
|
||||
* Assertion codes
|
||||
*/
|
||||
#define A_GPIO_OPEN_FAIL 100
|
||||
#define A_SERVO_OPEN_FAIL 101
|
||||
#define A_INPUTQ_OPEN_FAIL 102
|
||||
|
|
|
@ -0,0 +1,595 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file registers.c
|
||||
*
|
||||
* Implementation of the PX4IO register space.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include "px4io.h"
|
||||
#include "protocol.h"
|
||||
|
||||
static int registers_set_one(uint8_t page, uint8_t offset, uint16_t value);
|
||||
|
||||
/**
|
||||
* PAGE 0
|
||||
*
|
||||
* Static configuration parameters.
|
||||
*/
|
||||
static const uint16_t r_page_config[] = {
|
||||
[PX4IO_P_CONFIG_PROTOCOL_VERSION] = 1, /* XXX hardcoded magic number */
|
||||
[PX4IO_P_CONFIG_SOFTWARE_VERSION] = 1, /* XXX hardcoded magic number */
|
||||
[PX4IO_P_CONFIG_BOOTLOADER_VERSION] = 3, /* XXX hardcoded magic number */
|
||||
[PX4IO_P_CONFIG_MAX_TRANSFER] = 64, /* XXX hardcoded magic number */
|
||||
[PX4IO_P_CONFIG_CONTROL_COUNT] = PX4IO_CONTROL_CHANNELS,
|
||||
[PX4IO_P_CONFIG_ACTUATOR_COUNT] = IO_SERVO_COUNT,
|
||||
[PX4IO_P_CONFIG_RC_INPUT_COUNT] = MAX_CONTROL_CHANNELS,
|
||||
[PX4IO_P_CONFIG_ADC_INPUT_COUNT] = ADC_CHANNEL_COUNT,
|
||||
[PX4IO_P_CONFIG_RELAY_COUNT] = PX4IO_RELAY_CHANNELS,
|
||||
};
|
||||
|
||||
/**
|
||||
* PAGE 1
|
||||
*
|
||||
* Status values.
|
||||
*/
|
||||
uint16_t r_page_status[] = {
|
||||
[PX4IO_P_STATUS_FREEMEM] = 0,
|
||||
[PX4IO_P_STATUS_CPULOAD] = 0,
|
||||
[PX4IO_P_STATUS_FLAGS] = 0,
|
||||
[PX4IO_P_STATUS_ALARMS] = 0,
|
||||
[PX4IO_P_STATUS_VBATT] = 0,
|
||||
[PX4IO_P_STATUS_IBATT] = 0
|
||||
};
|
||||
|
||||
/**
|
||||
* PAGE 2
|
||||
*
|
||||
* Post-mixed actuator values.
|
||||
*/
|
||||
uint16_t r_page_actuators[IO_SERVO_COUNT];
|
||||
|
||||
/**
|
||||
* PAGE 3
|
||||
*
|
||||
* Servo PWM values
|
||||
*/
|
||||
uint16_t r_page_servos[IO_SERVO_COUNT];
|
||||
|
||||
/**
|
||||
* PAGE 4
|
||||
*
|
||||
* Raw RC input
|
||||
*/
|
||||
uint16_t r_page_raw_rc_input[] =
|
||||
{
|
||||
[PX4IO_P_RAW_RC_COUNT] = 0,
|
||||
[PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + MAX_CONTROL_CHANNELS)] = 0
|
||||
};
|
||||
|
||||
/**
|
||||
* PAGE 5
|
||||
*
|
||||
* Scaled/routed RC input
|
||||
*/
|
||||
uint16_t r_page_rc_input[] = {
|
||||
[PX4IO_P_RC_VALID] = 0,
|
||||
[PX4IO_P_RC_BASE ... (PX4IO_P_RC_BASE + MAX_CONTROL_CHANNELS)] = 0
|
||||
};
|
||||
|
||||
/**
|
||||
* PAGE 6
|
||||
*
|
||||
* Raw ADC input.
|
||||
*/
|
||||
uint16_t r_page_adc[ADC_CHANNEL_COUNT];
|
||||
|
||||
/**
|
||||
* PAGE 100
|
||||
*
|
||||
* Setup registers
|
||||
*/
|
||||
volatile uint16_t r_page_setup[] =
|
||||
{
|
||||
[PX4IO_P_SETUP_FEATURES] = 0,
|
||||
[PX4IO_P_SETUP_ARMING] = 0,
|
||||
[PX4IO_P_SETUP_PWM_RATES] = 0,
|
||||
[PX4IO_P_SETUP_PWM_LOWRATE] = 50,
|
||||
[PX4IO_P_SETUP_PWM_HIGHRATE] = 200,
|
||||
[PX4IO_P_SETUP_RELAYS] = 0,
|
||||
[PX4IO_P_SETUP_VBATT_SCALE] = 10000,
|
||||
[PX4IO_P_SETUP_IBATT_SCALE] = 0,
|
||||
[PX4IO_P_SETUP_IBATT_BIAS] = 0,
|
||||
[PX4IO_P_SETUP_SET_DEBUG] = 0,
|
||||
};
|
||||
|
||||
#define PX4IO_P_SETUP_FEATURES_VALID (0)
|
||||
#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_ARM_OK | \
|
||||
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | \
|
||||
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK)
|
||||
#define PX4IO_P_SETUP_RATES_VALID ((1 << IO_SERVO_COUNT) - 1)
|
||||
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
|
||||
|
||||
/**
|
||||
* PAGE 101
|
||||
*
|
||||
* Control values from the FMU.
|
||||
*/
|
||||
volatile uint16_t r_page_controls[PX4IO_CONTROL_CHANNELS];
|
||||
|
||||
/*
|
||||
* PAGE 102 does not have a buffer.
|
||||
*/
|
||||
|
||||
/**
|
||||
* PAGE 103
|
||||
*
|
||||
* R/C channel input configuration.
|
||||
*/
|
||||
uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE];
|
||||
|
||||
/* valid options */
|
||||
#define PX4IO_P_RC_CONFIG_OPTIONS_VALID (PX4IO_P_RC_CONFIG_OPTIONS_REVERSE | PX4IO_P_RC_CONFIG_OPTIONS_ENABLED)
|
||||
|
||||
/*
|
||||
* PAGE 104 uses r_page_servos.
|
||||
*/
|
||||
|
||||
/**
|
||||
* PAGE 105
|
||||
*
|
||||
* Failsafe servo PWM values
|
||||
*/
|
||||
uint16_t r_page_servo_failsafe[IO_SERVO_COUNT];
|
||||
|
||||
void
|
||||
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
|
||||
{
|
||||
|
||||
switch (page) {
|
||||
|
||||
/* handle bulk controls input */
|
||||
case PX4IO_PAGE_CONTROLS:
|
||||
|
||||
/* copy channel data */
|
||||
while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
|
||||
|
||||
/* XXX range-check value? */
|
||||
r_page_controls[offset] = *values;
|
||||
|
||||
offset++;
|
||||
num_values--;
|
||||
values++;
|
||||
}
|
||||
|
||||
system_state.fmu_data_received_time = hrt_absolute_time();
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
|
||||
r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_FMU_LOST;
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RAW_PWM;
|
||||
|
||||
break;
|
||||
|
||||
/* handle raw PWM input */
|
||||
case PX4IO_PAGE_DIRECT_PWM:
|
||||
|
||||
/* copy channel data */
|
||||
while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
|
||||
|
||||
/* XXX range-check value? */
|
||||
r_page_servos[offset] = *values;
|
||||
|
||||
offset++;
|
||||
num_values--;
|
||||
values++;
|
||||
}
|
||||
|
||||
system_state.fmu_data_received_time = hrt_absolute_time();
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM;
|
||||
|
||||
break;
|
||||
|
||||
/* handle setup for servo failsafe values */
|
||||
case PX4IO_PAGE_FAILSAFE_PWM:
|
||||
|
||||
/* copy channel data */
|
||||
while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
|
||||
|
||||
/* XXX range-check value? */
|
||||
r_page_servo_failsafe[offset] = *values;
|
||||
|
||||
offset++;
|
||||
num_values--;
|
||||
values++;
|
||||
}
|
||||
break;
|
||||
|
||||
/* handle text going to the mixer parser */
|
||||
case PX4IO_PAGE_MIXERLOAD:
|
||||
mixer_handle_text(values, num_values * sizeof(*values));
|
||||
break;
|
||||
|
||||
default:
|
||||
/* avoid offset wrap */
|
||||
if ((offset + num_values) > 255)
|
||||
num_values = 255 - offset;
|
||||
|
||||
/* iterate individual registers, set each in turn */
|
||||
while (num_values--) {
|
||||
if (registers_set_one(page, offset, *values))
|
||||
break;
|
||||
offset++;
|
||||
values++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static int
|
||||
registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
||||
{
|
||||
switch (page) {
|
||||
|
||||
case PX4IO_PAGE_STATUS:
|
||||
switch (offset) {
|
||||
case PX4IO_P_STATUS_ALARMS:
|
||||
/* clear bits being written */
|
||||
r_status_alarms &= ~value;
|
||||
break;
|
||||
|
||||
case PX4IO_P_STATUS_FLAGS:
|
||||
/*
|
||||
* Allow FMU override of arming state (to allow in-air restores),
|
||||
* but only if the arming state is not in sync on the IO side.
|
||||
*/
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
|
||||
r_status_flags = value;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
/* just ignore writes to other registers in this page */
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case PX4IO_PAGE_SETUP:
|
||||
switch (offset) {
|
||||
case PX4IO_P_SETUP_FEATURES:
|
||||
|
||||
value &= PX4IO_P_SETUP_FEATURES_VALID;
|
||||
r_setup_features = value;
|
||||
|
||||
/* no implemented feature selection at this point */
|
||||
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_ARMING:
|
||||
|
||||
value &= PX4IO_P_SETUP_ARMING_VALID;
|
||||
|
||||
/*
|
||||
* Update arming state - disarm if no longer OK.
|
||||
* This builds on the requirement that the FMU driver
|
||||
* asks about the FMU arming state on initialization,
|
||||
* so that an in-air reset of FMU can not lead to a
|
||||
* lockup of the IO arming state.
|
||||
*/
|
||||
if ((r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) && !(value & PX4IO_P_SETUP_ARMING_ARM_OK)) {
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
|
||||
}
|
||||
|
||||
r_setup_arming = value;
|
||||
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_PWM_RATES:
|
||||
value &= PX4IO_P_SETUP_RATES_VALID;
|
||||
r_setup_pwm_rates = value;
|
||||
/* XXX re-configure timers */
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_PWM_LOWRATE:
|
||||
if (value < 50)
|
||||
value = 50;
|
||||
if (value > 400)
|
||||
value = 400;
|
||||
r_setup_pwm_lowrate = value;
|
||||
/* XXX re-configure timers */
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_PWM_HIGHRATE:
|
||||
if (value < 50)
|
||||
value = 50;
|
||||
if (value > 400)
|
||||
value = 400;
|
||||
r_setup_pwm_highrate = value;
|
||||
/* XXX re-configure timers */
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_RELAYS:
|
||||
value &= PX4IO_P_SETUP_RELAYS_VALID;
|
||||
r_setup_relays = value;
|
||||
POWER_RELAY1(value & (1 << 0) ? 1 : 0);
|
||||
POWER_RELAY2(value & (1 << 1) ? 1 : 0);
|
||||
POWER_ACC1(value & (1 << 2) ? 1 : 0);
|
||||
POWER_ACC2(value & (1 << 3) ? 1 : 0);
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_SET_DEBUG:
|
||||
r_page_setup[PX4IO_P_SETUP_SET_DEBUG] = value;
|
||||
isr_debug(0, "set debug %u\n", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG]);
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
break;
|
||||
|
||||
case PX4IO_PAGE_RC_CONFIG: {
|
||||
|
||||
/* do not allow a RC config change while fully armed */
|
||||
if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) &&
|
||||
/* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
|
||||
break;
|
||||
}
|
||||
|
||||
unsigned channel = offset / PX4IO_P_RC_CONFIG_STRIDE;
|
||||
unsigned index = offset - channel * PX4IO_P_RC_CONFIG_STRIDE;
|
||||
uint16_t *conf = &r_page_rc_input_config[channel * PX4IO_P_RC_CONFIG_STRIDE];
|
||||
|
||||
if (channel >= MAX_CONTROL_CHANNELS)
|
||||
return -1;
|
||||
|
||||
/* disable the channel until we have a chance to sanity-check it */
|
||||
conf[PX4IO_P_RC_CONFIG_OPTIONS] &= PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
|
||||
|
||||
switch (index) {
|
||||
|
||||
case PX4IO_P_RC_CONFIG_MIN:
|
||||
case PX4IO_P_RC_CONFIG_CENTER:
|
||||
case PX4IO_P_RC_CONFIG_MAX:
|
||||
case PX4IO_P_RC_CONFIG_DEADZONE:
|
||||
case PX4IO_P_RC_CONFIG_ASSIGNMENT:
|
||||
conf[index] = value;
|
||||
break;
|
||||
|
||||
case PX4IO_P_RC_CONFIG_OPTIONS:
|
||||
value &= PX4IO_P_RC_CONFIG_OPTIONS_VALID;
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
|
||||
|
||||
/* set all options except the enabled option */
|
||||
conf[index] = value & ~PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
|
||||
|
||||
/* should the channel be enabled? */
|
||||
/* this option is normally set last */
|
||||
if (value & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
|
||||
uint8_t count = 0;
|
||||
|
||||
/* assert min..center..max ordering */
|
||||
if (conf[PX4IO_P_RC_CONFIG_MIN] < 500) {
|
||||
count++;
|
||||
}
|
||||
if (conf[PX4IO_P_RC_CONFIG_MAX] > 2500) {
|
||||
count++;
|
||||
}
|
||||
if (conf[PX4IO_P_RC_CONFIG_CENTER] < conf[PX4IO_P_RC_CONFIG_MIN]) {
|
||||
count++;
|
||||
}
|
||||
if (conf[PX4IO_P_RC_CONFIG_CENTER] > conf[PX4IO_P_RC_CONFIG_MAX]) {
|
||||
count++;
|
||||
}
|
||||
|
||||
/* assert deadzone is sane */
|
||||
if (conf[PX4IO_P_RC_CONFIG_DEADZONE] > 500) {
|
||||
count++;
|
||||
}
|
||||
// The following check isn't needed as constraint checks in controls.c will catch this.
|
||||
//if (conf[PX4IO_P_RC_CONFIG_MIN] > (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
// count++;
|
||||
//}
|
||||
//if (conf[PX4IO_P_RC_CONFIG_MAX] < (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
|
||||
// count++;
|
||||
//}
|
||||
if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= MAX_CONTROL_CHANNELS) {
|
||||
count++;
|
||||
}
|
||||
|
||||
/* sanity checks pass, enable channel */
|
||||
if (count) {
|
||||
isr_debug(0, "ERROR: %d config error(s) for RC%d.\n", count, (channel + 1));
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_INIT_OK;
|
||||
} else {
|
||||
conf[index] |= PX4IO_P_RC_CONFIG_OPTIONS_ENABLED;
|
||||
}
|
||||
}
|
||||
break;
|
||||
/* inner switch: case PX4IO_P_RC_CONFIG_OPTIONS */
|
||||
|
||||
}
|
||||
break;
|
||||
/* case PX4IO_RC_PAGE_CONFIG */
|
||||
}
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t last_page;
|
||||
uint8_t last_offset;
|
||||
|
||||
int
|
||||
registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values)
|
||||
{
|
||||
#define SELECT_PAGE(_page_name) \
|
||||
do { \
|
||||
*values = &_page_name[0]; \
|
||||
*num_values = sizeof(_page_name) / sizeof(_page_name[0]); \
|
||||
} while(0)
|
||||
|
||||
switch (page) {
|
||||
|
||||
/*
|
||||
* Handle pages that are updated dynamically at read time.
|
||||
*/
|
||||
case PX4IO_PAGE_STATUS:
|
||||
/* PX4IO_P_STATUS_FREEMEM */
|
||||
{
|
||||
struct mallinfo minfo = mallinfo();
|
||||
r_page_status[PX4IO_P_STATUS_FREEMEM] = minfo.fordblks;
|
||||
}
|
||||
|
||||
/* XXX PX4IO_P_STATUS_CPULOAD */
|
||||
|
||||
/* PX4IO_P_STATUS_FLAGS maintained externally */
|
||||
|
||||
/* PX4IO_P_STATUS_ALARMS maintained externally */
|
||||
|
||||
/* PX4IO_P_STATUS_VBATT */
|
||||
{
|
||||
/*
|
||||
* Coefficients here derived by measurement of the 5-16V
|
||||
* range on one unit:
|
||||
*
|
||||
* V counts
|
||||
* 5 1001
|
||||
* 6 1219
|
||||
* 7 1436
|
||||
* 8 1653
|
||||
* 9 1870
|
||||
* 10 2086
|
||||
* 11 2303
|
||||
* 12 2522
|
||||
* 13 2738
|
||||
* 14 2956
|
||||
* 15 3172
|
||||
* 16 3389
|
||||
*
|
||||
* slope = 0.0046067
|
||||
* intercept = 0.3863
|
||||
*
|
||||
* Intercept corrected for best results @ 12V.
|
||||
*/
|
||||
unsigned counts = adc_measure(ADC_VBATT);
|
||||
unsigned mV = (4150 + (counts * 46)) / 10 - 200;
|
||||
unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000;
|
||||
|
||||
r_page_status[PX4IO_P_STATUS_VBATT] = corrected;
|
||||
}
|
||||
|
||||
/* PX4IO_P_STATUS_IBATT */
|
||||
{
|
||||
unsigned counts = adc_measure(ADC_VBATT);
|
||||
unsigned scaled = (counts * r_page_setup[PX4IO_P_SETUP_IBATT_SCALE]) / 10000;
|
||||
int corrected = scaled + REG_TO_SIGNED(r_page_setup[PX4IO_P_SETUP_IBATT_BIAS]);
|
||||
if (corrected < 0)
|
||||
corrected = 0;
|
||||
r_page_status[PX4IO_P_STATUS_IBATT] = corrected;
|
||||
}
|
||||
|
||||
SELECT_PAGE(r_page_status);
|
||||
break;
|
||||
|
||||
case PX4IO_PAGE_RAW_ADC_INPUT:
|
||||
r_page_adc[0] = adc_measure(ADC_VBATT);
|
||||
r_page_adc[1] = adc_measure(ADC_IN5);
|
||||
|
||||
SELECT_PAGE(r_page_adc);
|
||||
break;
|
||||
|
||||
/*
|
||||
* Pages that are just a straight read of the register state.
|
||||
*/
|
||||
|
||||
/* status pages */
|
||||
case PX4IO_PAGE_CONFIG:
|
||||
SELECT_PAGE(r_page_config);
|
||||
break;
|
||||
case PX4IO_PAGE_ACTUATORS:
|
||||
SELECT_PAGE(r_page_actuators);
|
||||
break;
|
||||
case PX4IO_PAGE_SERVOS:
|
||||
SELECT_PAGE(r_page_servos);
|
||||
break;
|
||||
case PX4IO_PAGE_RAW_RC_INPUT:
|
||||
SELECT_PAGE(r_page_raw_rc_input);
|
||||
break;
|
||||
case PX4IO_PAGE_RC_INPUT:
|
||||
SELECT_PAGE(r_page_rc_input);
|
||||
break;
|
||||
|
||||
/* readback of input pages */
|
||||
case PX4IO_PAGE_SETUP:
|
||||
SELECT_PAGE(r_page_setup);
|
||||
break;
|
||||
case PX4IO_PAGE_CONTROLS:
|
||||
SELECT_PAGE(r_page_controls);
|
||||
break;
|
||||
case PX4IO_PAGE_RC_CONFIG:
|
||||
SELECT_PAGE(r_page_rc_input_config);
|
||||
break;
|
||||
case PX4IO_PAGE_DIRECT_PWM:
|
||||
SELECT_PAGE(r_page_servos);
|
||||
break;
|
||||
case PX4IO_PAGE_FAILSAFE_PWM:
|
||||
SELECT_PAGE(r_page_servo_failsafe);
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
#undef SELECT_PAGE
|
||||
#undef COPY_PAGE
|
||||
|
||||
last_page = page;
|
||||
last_offset = offset;
|
||||
|
||||
/* if the offset is at or beyond the end of the page, we have no data */
|
||||
if (offset >= *num_values)
|
||||
return -1;
|
||||
|
||||
/* correct the data pointer and count for the offset */
|
||||
*values += offset;
|
||||
*num_values -= offset;
|
||||
|
||||
return 0;
|
||||
}
|
|
@ -36,15 +36,8 @@
|
|||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <debug.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/clock.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
|
@ -116,30 +109,28 @@ safety_check_button(void *arg)
|
|||
* state machine, keep ARM_COUNTER_THRESHOLD the same
|
||||
* length in all cases of the if/else struct below.
|
||||
*/
|
||||
if (safety_button_pressed && !system_state.armed) {
|
||||
if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
|
||||
|
||||
if (counter < ARM_COUNTER_THRESHOLD) {
|
||||
counter++;
|
||||
|
||||
} else if (counter == ARM_COUNTER_THRESHOLD) {
|
||||
/* change to armed state and notify the FMU */
|
||||
system_state.armed = true;
|
||||
/* switch to armed state */
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_ARMED;
|
||||
counter++;
|
||||
system_state.fmu_report_due = true;
|
||||
}
|
||||
|
||||
/* Disarm quickly */
|
||||
|
||||
} else if (safety_button_pressed && system_state.armed) {
|
||||
} else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) {
|
||||
|
||||
if (counter < ARM_COUNTER_THRESHOLD) {
|
||||
counter++;
|
||||
|
||||
} else if (counter == ARM_COUNTER_THRESHOLD) {
|
||||
/* change to disarmed state and notify the FMU */
|
||||
system_state.armed = false;
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
|
||||
counter++;
|
||||
system_state.fmu_report_due = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
|
@ -149,18 +140,18 @@ safety_check_button(void *arg)
|
|||
/* Select the appropriate LED flash pattern depending on the current IO/FMU arm state */
|
||||
uint16_t pattern = LED_PATTERN_SAFE;
|
||||
|
||||
if (system_state.armed) {
|
||||
if (system_state.arm_ok) {
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) {
|
||||
if (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) {
|
||||
pattern = LED_PATTERN_IO_FMU_ARMED;
|
||||
|
||||
} else {
|
||||
pattern = LED_PATTERN_IO_ARMED;
|
||||
}
|
||||
|
||||
} else if (system_state.arm_ok) {
|
||||
} else if (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) {
|
||||
pattern = LED_PATTERN_FMU_ARMED;
|
||||
|
||||
} else if (system_state.vector_flight_mode_ok) {
|
||||
} else if (r_setup_arming & PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK) {
|
||||
pattern = LED_PATTERN_VECTOR_FLIGHT_MODE_OK;
|
||||
}
|
||||
|
||||
|
@ -185,12 +176,17 @@ heartbeat_blink(void *arg)
|
|||
static void
|
||||
failsafe_blink(void *arg)
|
||||
{
|
||||
/* indicate that a serious initialisation error occured */
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)) {
|
||||
LED_AMBER(true);
|
||||
return;
|
||||
}
|
||||
|
||||
static bool failsafe = false;
|
||||
|
||||
/* blink the failsafe LED if we don't have FMU input */
|
||||
if (!system_state.mixer_fmu_available) {
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
|
||||
failsafe = !failsafe;
|
||||
|
||||
} else {
|
||||
failsafe = false;
|
||||
}
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
#include "debug.h"
|
||||
|
||||
#define SBUS_FRAME_SIZE 25
|
||||
#define SBUS_INPUT_CHANNELS 18
|
||||
#define SBUS_INPUT_CHANNELS 16
|
||||
|
||||
static int sbus_fd = -1;
|
||||
|
||||
|
@ -66,13 +66,13 @@ static unsigned partial_frame_count;
|
|||
|
||||
unsigned sbus_frame_drops;
|
||||
|
||||
static void sbus_decode(hrt_abstime frame_time);
|
||||
static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values);
|
||||
|
||||
int
|
||||
sbus_init(const char *device)
|
||||
{
|
||||
if (sbus_fd < 0)
|
||||
sbus_fd = open(device, O_RDONLY);
|
||||
sbus_fd = open(device, O_RDONLY | O_NONBLOCK);
|
||||
|
||||
if (sbus_fd >= 0) {
|
||||
struct termios t;
|
||||
|
@ -97,7 +97,7 @@ sbus_init(const char *device)
|
|||
}
|
||||
|
||||
bool
|
||||
sbus_input(void)
|
||||
sbus_input(uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
ssize_t ret;
|
||||
hrt_abstime now;
|
||||
|
@ -134,7 +134,7 @@ sbus_input(void)
|
|||
|
||||
/* if the read failed for any reason, just give up here */
|
||||
if (ret < 1)
|
||||
goto out;
|
||||
return false;
|
||||
|
||||
last_rx_time = now;
|
||||
|
||||
|
@ -147,20 +147,14 @@ sbus_input(void)
|
|||
* If we don't have a full frame, return
|
||||
*/
|
||||
if (partial_frame_count < SBUS_FRAME_SIZE)
|
||||
goto out;
|
||||
return false;
|
||||
|
||||
/*
|
||||
* Great, it looks like we might have a frame. Go ahead and
|
||||
* decode it.
|
||||
*/
|
||||
sbus_decode(now);
|
||||
partial_frame_count = 0;
|
||||
|
||||
out:
|
||||
/*
|
||||
* If we have seen a frame in the last 200ms, we consider ourselves 'locked'
|
||||
*/
|
||||
return (now - last_frame_time) < 200000;
|
||||
return sbus_decode(now, values, num_values);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -199,13 +193,13 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
|
|||
/* 15 */ { {20, 5, 0x07, 0}, {21, 0, 0xff, 3}, { 0, 0, 0x00, 0} }
|
||||
};
|
||||
|
||||
static void
|
||||
sbus_decode(hrt_abstime frame_time)
|
||||
static bool
|
||||
sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
|
||||
{
|
||||
/* check frame boundary markers to avoid out-of-sync cases */
|
||||
if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
|
||||
sbus_frame_drops++;
|
||||
return;
|
||||
return false;
|
||||
}
|
||||
|
||||
/* if the failsafe or connection lost bit is set, we consider the frame invalid */
|
||||
|
@ -213,8 +207,8 @@ sbus_decode(hrt_abstime frame_time)
|
|||
(frame[23] & (1 << 3))) { /* failsafe */
|
||||
|
||||
/* actively announce signal loss */
|
||||
system_state.rc_channels = 0;
|
||||
return 1;
|
||||
*values = 0;
|
||||
return false;
|
||||
}
|
||||
|
||||
/* we have received something we think is a frame */
|
||||
|
@ -241,23 +235,21 @@ sbus_decode(hrt_abstime frame_time)
|
|||
}
|
||||
|
||||
/* convert 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
|
||||
system_state.rc_channel_data[channel] = (value / 2) + 998;
|
||||
values[channel] = (value / 2) + 998;
|
||||
}
|
||||
|
||||
/* decode switch channels if data fields are wide enough */
|
||||
if (chancount > 17) {
|
||||
if (PX4IO_INPUT_CHANNELS > 17 && chancount > 15) {
|
||||
chancount = 18;
|
||||
|
||||
/* channel 17 (index 16) */
|
||||
system_state.rc_channel_data[16] = (frame[23] & (1 << 0)) * 1000 + 998;
|
||||
values[16] = (frame[23] & (1 << 0)) * 1000 + 998;
|
||||
/* channel 18 (index 17) */
|
||||
system_state.rc_channel_data[17] = (frame[23] & (1 << 1)) * 1000 + 998;
|
||||
values[17] = (frame[23] & (1 << 1)) * 1000 + 998;
|
||||
}
|
||||
|
||||
/* note the number of channels decoded */
|
||||
system_state.rc_channels = chancount;
|
||||
*num_values = chancount;
|
||||
|
||||
/* and note that we have received data from the R/C controller */
|
||||
system_state.rc_channels_timestamp = frame_time;
|
||||
|
||||
/* trigger an immediate report to the FMU */
|
||||
system_state.fmu_report_due = true;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -1084,36 +1084,6 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
|
|||
void
|
||||
Sensors::ppm_poll()
|
||||
{
|
||||
/* fake low-level driver, directly pulling from driver variables */
|
||||
static orb_advert_t rc_input_pub = -1;
|
||||
struct rc_input_values raw;
|
||||
|
||||
raw.timestamp = ppm_last_valid_decode;
|
||||
/* we are accepting this message */
|
||||
_ppm_last_valid = ppm_last_valid_decode;
|
||||
|
||||
/*
|
||||
* relying on two decoded channels is very noise-prone,
|
||||
* in particular if nothing is connected to the pins.
|
||||
* requiring a minimum of four channels
|
||||
*/
|
||||
if (ppm_decoded_channels > 4 && hrt_absolute_time() - _ppm_last_valid < PPM_INPUT_TIMEOUT_INTERVAL) {
|
||||
|
||||
for (unsigned i = 0; i < ppm_decoded_channels; i++) {
|
||||
raw.values[i] = ppm_buffer[i];
|
||||
}
|
||||
|
||||
raw.channel_count = ppm_decoded_channels;
|
||||
|
||||
/* publish to object request broker */
|
||||
if (rc_input_pub <= 0) {
|
||||
rc_input_pub = orb_advertise(ORB_ID(input_rc), &raw);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(input_rc), rc_input_pub, &raw);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
|
||||
bool rc_updated;
|
||||
|
@ -1159,31 +1129,45 @@ Sensors::ppm_poll()
|
|||
/* Read out values from raw message */
|
||||
for (unsigned int i = 0; i < channel_limit; i++) {
|
||||
|
||||
/* scale around the mid point differently for lower and upper range */
|
||||
/*
|
||||
* 1) Constrain to min/max values, as later processing depends on bounds.
|
||||
*/
|
||||
if (rc_input.values[i] < _parameters.min[i])
|
||||
rc_input.values[i] = _parameters.min[i];
|
||||
if (rc_input.values[i] > _parameters.max[i])
|
||||
rc_input.values[i] = _parameters.max[i];
|
||||
|
||||
/*
|
||||
* 2) Scale around the mid point differently for lower and upper range.
|
||||
*
|
||||
* This is necessary as they don't share the same endpoints and slope.
|
||||
*
|
||||
* First normalize to 0..1 range with correct sign (below or above center),
|
||||
* the total range is 2 (-1..1).
|
||||
* If center (trim) == min, scale to 0..1, if center (trim) == max,
|
||||
* scale to -1..0.
|
||||
*
|
||||
* As the min and max bounds were enforced in step 1), division by zero
|
||||
* cannot occur, as for the case of center == min or center == max the if
|
||||
* statement is mutually exclusive with the arithmetic NaN case.
|
||||
*
|
||||
* DO NOT REMOVE OR ALTER STEP 1!
|
||||
*/
|
||||
if (rc_input.values[i] > (_parameters.trim[i] + _parameters.dz[i])) {
|
||||
_rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i]) / (float)(_parameters.max[i] - _parameters.trim[i]);
|
||||
_rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]);
|
||||
|
||||
} else if (rc_input.values[i] < (_parameters.trim[i] - _parameters.dz[i])) {
|
||||
/* division by zero impossible for trim == min (as for throttle), as this falls in the above if clause */
|
||||
_rc.chan[i].scaled = -((_parameters.trim[i] - rc_input.values[i]) / (float)(_parameters.trim[i] - _parameters.min[i]));
|
||||
_rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]);
|
||||
|
||||
} else {
|
||||
/* in the configured dead zone, output zero */
|
||||
_rc.chan[i].scaled = 0.0f;
|
||||
}
|
||||
|
||||
/* reverse channel if required */
|
||||
if (i == (int)_rc.function[THROTTLE]) {
|
||||
if ((int)_parameters.rev[i] == -1) {
|
||||
_rc.chan[i].scaled = 1.0f + -1.0f * _rc.chan[i].scaled;
|
||||
}
|
||||
|
||||
} else {
|
||||
_rc.chan[i].scaled *= _parameters.rev[i];
|
||||
}
|
||||
|
||||
/* handle any parameter-induced blowups */
|
||||
if (isnan(_rc.chan[i].scaled) || isinf(_rc.chan[i].scaled))
|
||||
if (!isfinite(_rc.chan[i].scaled))
|
||||
_rc.chan[i].scaled = 0.0f;
|
||||
}
|
||||
|
||||
|
|
|
@ -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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build the i2c test tool.
|
||||
#
|
||||
|
||||
APPNAME = i2c
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 4096
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
|
@ -0,0 +1,140 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file i2c.c
|
||||
*
|
||||
* i2c hacking tool
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/mount.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/err.h"
|
||||
|
||||
#ifndef PX4_I2C_BUS_ONBOARD
|
||||
# error PX4_I2C_BUS_ONBOARD not defined, no device interface
|
||||
#endif
|
||||
#ifndef PX4_I2C_OBDEV_PX4IO
|
||||
# error PX4_I2C_OBDEV_PX4IO not defined
|
||||
#endif
|
||||
|
||||
__EXPORT int i2c_main(int argc, char *argv[]);
|
||||
|
||||
static int transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len);
|
||||
|
||||
static struct i2c_dev_s *i2c;
|
||||
|
||||
int i2c_main(int argc, char *argv[])
|
||||
{
|
||||
/* find the right I2C */
|
||||
i2c = up_i2cinitialize(PX4_I2C_BUS_ONBOARD);
|
||||
|
||||
if (i2c == NULL)
|
||||
errx(1, "failed to locate I2C bus");
|
||||
|
||||
usleep(100000);
|
||||
|
||||
uint8_t buf[] = { 0, 4};
|
||||
int ret = transfer(PX4_I2C_OBDEV_PX4IO, buf, sizeof(buf), NULL, 0);
|
||||
|
||||
if (ret)
|
||||
errx(1, "send failed - %d", ret);
|
||||
|
||||
uint32_t val;
|
||||
ret = transfer(PX4_I2C_OBDEV_PX4IO, NULL, 0, (uint8_t *)&val, sizeof(val));
|
||||
if (ret)
|
||||
errx(1, "recive failed - %d", ret);
|
||||
|
||||
errx(0, "got 0x%08x", val);
|
||||
}
|
||||
|
||||
static int
|
||||
transfer(uint8_t address, uint8_t *send, unsigned send_len, uint8_t *recv, unsigned recv_len)
|
||||
{
|
||||
struct i2c_msg_s msgv[2];
|
||||
unsigned msgs;
|
||||
int ret;
|
||||
|
||||
// debug("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
|
||||
|
||||
msgs = 0;
|
||||
|
||||
if (send_len > 0) {
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = 0;
|
||||
msgv[msgs].buffer = send;
|
||||
msgv[msgs].length = send_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (recv_len > 0) {
|
||||
msgv[msgs].addr = address;
|
||||
msgv[msgs].flags = I2C_M_READ;
|
||||
msgv[msgs].buffer = recv;
|
||||
msgv[msgs].length = recv_len;
|
||||
msgs++;
|
||||
}
|
||||
|
||||
if (msgs == 0)
|
||||
return -1;
|
||||
|
||||
/*
|
||||
* I2C architecture means there is an unavoidable race here
|
||||
* if there are any devices on the bus with a different frequency
|
||||
* preference. Really, this is pointless.
|
||||
*/
|
||||
I2C_SETFREQUENCY(i2c, 400000);
|
||||
ret = I2C_TRANSFER(i2c, &msgv[0], msgs);
|
||||
|
||||
// reset the I2C bus to unwedge on error
|
||||
if (ret != OK)
|
||||
up_i2creset(i2c);
|
||||
|
||||
return ret;
|
||||
}
|
|
@ -117,7 +117,23 @@ load(const char *devname, const char *fname)
|
|||
if ((strlen(line) < 2) || !isupper(line[0]) || (line[1] != ':'))
|
||||
continue;
|
||||
|
||||
/* XXX an optimisation here would be to strip extra whitespace */
|
||||
/* compact whitespace in the buffer */
|
||||
char *t, *f;
|
||||
for (f = buf; *f != '\0'; f++) {
|
||||
/* scan for space characters */
|
||||
if (*f == ' ') {
|
||||
/* look for additional spaces */
|
||||
t = f + 1;
|
||||
while (*t == ' ')
|
||||
t++;
|
||||
if (*t == '\0') {
|
||||
/* strip trailing whitespace */
|
||||
*f = '\0';
|
||||
} else if (t > (f + 1)) {
|
||||
memmove(f + 1, t, strlen(t) + 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* if the line is too long to fit in the buffer, bail */
|
||||
if ((strlen(line) + strlen(buf) + 1) >= sizeof(buf))
|
||||
|
|
|
@ -54,6 +54,7 @@
|
|||
#include "mixer.h"
|
||||
|
||||
Mixer::Mixer(ControlCallback control_cb, uintptr_t cb_handle) :
|
||||
_next(nullptr),
|
||||
_control_cb(control_cb),
|
||||
_cb_handle(cb_handle)
|
||||
{
|
||||
|
|
|
@ -160,7 +160,7 @@ public:
|
|||
* @param control_cb Callback invoked when reading controls.
|
||||
*/
|
||||
Mixer(ControlCallback control_cb, uintptr_t cb_handle);
|
||||
~Mixer() {};
|
||||
virtual ~Mixer() {};
|
||||
|
||||
/**
|
||||
* Perform the mixing function.
|
||||
|
|
|
@ -93,6 +93,7 @@ MixerGroup::reset()
|
|||
mixer = _first;
|
||||
_first = mixer->_next;
|
||||
delete mixer;
|
||||
mixer = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -53,6 +53,9 @@ ORB_DEFINE(sensor_gyro, struct gyro_report);
|
|||
#include <drivers/drv_baro.h>
|
||||
ORB_DEFINE(sensor_baro, struct baro_report);
|
||||
|
||||
#include <drivers/drv_range_finder.h>
|
||||
ORB_DEFINE(sensor_range_finder, struct range_finder_report);
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
ORB_DEFINE(output_pwm, struct pwm_output_values);
|
||||
|
||||
|
|
|
@ -37,8 +37,8 @@
|
|||
* Actuator control topics - mixer inputs.
|
||||
*
|
||||
* Values published to these topics are the outputs of the vehicle control
|
||||
* system, and are expected to be mixed and used to drive the actuators
|
||||
* (servos, speed controls, etc.) that operate the vehicle.
|
||||
* system and mixing process; they are the control-scale values that are
|
||||
* then fed to the actual actuator driver.
|
||||
*
|
||||
* Each topic can be published by a single controller
|
||||
*/
|
||||
|
|
|
@ -71,7 +71,8 @@ enum SUBSYSTEM_TYPE
|
|||
SUBSYSTEM_TYPE_YAWPOSITION = 4096,
|
||||
SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384,
|
||||
SUBSYSTEM_TYPE_POSITIONCONTROL = 32768,
|
||||
SUBSYSTEM_TYPE_MOTORCONTROL = 65536
|
||||
SUBSYSTEM_TYPE_MOTORCONTROL = 65536,
|
||||
SUBSYSTEM_TYPE_RANGEFINDER = 131072
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -156,7 +156,9 @@ struct vehicle_status_s
|
|||
enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
|
||||
enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
|
||||
enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
|
||||
int32_t system_type; /**< system type, inspired by MAVLinks VEHICLE_TYPE enum */
|
||||
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
|
||||
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
|
||||
int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
|
||||
|
||||
/* system flags - these represent the state predicates */
|
||||
|
||||
|
@ -210,6 +212,7 @@ struct vehicle_status_s
|
|||
bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
|
||||
bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
|
||||
bool flag_valid_launch_position; /**< indicates a valid launch position */
|
||||
bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
|
||||
bool flag_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
|
||||
};
|
||||
|
||||
|
|
|
@ -185,6 +185,22 @@ enum stm32_trace_e
|
|||
I2CEVENT_ERROR /* Error occurred, param = 0 */
|
||||
};
|
||||
|
||||
#ifdef CONFIG_I2C_TRACE
|
||||
static const char *stm32_trace_names[] = {
|
||||
"NONE ",
|
||||
"SENDADDR ",
|
||||
"SENDBYTE ",
|
||||
"ITBUFEN ",
|
||||
"RCVBYTE ",
|
||||
"REITBUFEN ",
|
||||
"DISITBUFEN",
|
||||
"BTFNOSTART",
|
||||
"BTFRESTART",
|
||||
"BTFSTOP ",
|
||||
"ERROR "
|
||||
};
|
||||
#endif
|
||||
|
||||
/* Trace data */
|
||||
|
||||
struct stm32_trace_s
|
||||
|
@ -846,6 +862,7 @@ static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
|
|||
|
||||
trace->event = event;
|
||||
trace->parm = parm;
|
||||
trace->time = clock_systimer();
|
||||
|
||||
/* Bump up the trace index (unless we are out of trace entries) */
|
||||
|
||||
|
@ -869,8 +886,8 @@ static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv)
|
|||
for (i = 0; i <= priv->tndx; i++)
|
||||
{
|
||||
trace = &priv->trace[i];
|
||||
syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %2d PARM: %08x TIME: %d\n",
|
||||
i+1, trace->status, trace->count, trace->event, trace->parm,
|
||||
syslog("%2d. STATUS: %08x COUNT: %3d EVENT: %s PARM: %08x TIME: %d\n",
|
||||
i+1, trace->status, trace->count, stm32_trace_names[trace->event], trace->parm,
|
||||
trace->time - priv->start_time);
|
||||
}
|
||||
}
|
||||
|
@ -1620,8 +1637,8 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
|
|||
status = stm32_i2c_getstatus(priv);
|
||||
errval = ETIMEDOUT;
|
||||
|
||||
i2cdbg("Timed out: CR1: %04x status: %08x\n",
|
||||
stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET), status);
|
||||
i2cdbg("Timed out: CR1: %04x status: %08x after %d\n",
|
||||
stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET), status, timeout_us);
|
||||
|
||||
/* "Note: When the STOP, START or PEC bit is set, the software must
|
||||
* not perform any write access to I2C_CR1 before this bit is
|
||||
|
@ -2005,7 +2022,7 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
|
|||
|
||||
/* Give up if we have tried too hard */
|
||||
|
||||
if (clock_count++ > 1000)
|
||||
if (clock_count++ > CONFIG_STM32_I2CTIMEOTICKS)
|
||||
{
|
||||
goto out;
|
||||
}
|
||||
|
|
|
@ -299,7 +299,7 @@
|
|||
#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
|
||||
|
||||
#define PX4_I2C_OBDEV_PX4IO_BL 0x18
|
||||
#define PX4_I2C_OBDEV_PX4IO 0x19
|
||||
#define PX4_I2C_OBDEV_PX4IO 0x1a
|
||||
|
||||
/*
|
||||
* SPI
|
||||
|
|
|
@ -46,14 +46,18 @@ CONFIGURED_APPS += systemlib
|
|||
CONFIGURED_APPS += systemlib/mixer
|
||||
|
||||
# Math library
|
||||
ifneq ($(CONFIG_APM),y)
|
||||
CONFIGURED_APPS += mathlib
|
||||
CONFIGURED_APPS += mathlib/CMSIS
|
||||
CONFIGURED_APPS += examples/math_demo
|
||||
endif
|
||||
|
||||
# Control library
|
||||
ifneq ($(CONFIG_APM),y)
|
||||
CONFIGURED_APPS += controllib
|
||||
CONFIGURED_APPS += examples/control_demo
|
||||
CONFIGURED_APPS += examples/kalman_demo
|
||||
endif
|
||||
|
||||
# System utility commands
|
||||
CONFIGURED_APPS += systemcmds/reboot
|
||||
|
@ -77,7 +81,7 @@ CONFIGURED_APPS += systemcmds/delay_test
|
|||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
CONFIGURED_APPS += examples/px4_mavlink_debug
|
||||
# CONFIGURED_APPS += examples/px4_mavlink_debug
|
||||
|
||||
# Shared object broker; required by many parts of the system.
|
||||
CONFIGURED_APPS += uORB
|
||||
|
@ -87,6 +91,8 @@ CONFIGURED_APPS += mavlink_onboard
|
|||
CONFIGURED_APPS += commander
|
||||
CONFIGURED_APPS += sdlog
|
||||
CONFIGURED_APPS += sensors
|
||||
|
||||
ifneq ($(CONFIG_APM),y)
|
||||
CONFIGURED_APPS += ardrone_interface
|
||||
CONFIGURED_APPS += multirotor_att_control
|
||||
CONFIGURED_APPS += multirotor_pos_control
|
||||
|
@ -96,10 +102,11 @@ CONFIGURED_APPS += fixedwing_pos_control
|
|||
CONFIGURED_APPS += position_estimator
|
||||
CONFIGURED_APPS += attitude_estimator_ekf
|
||||
CONFIGURED_APPS += hott_telemetry
|
||||
endif
|
||||
|
||||
# Hacking tools
|
||||
#CONFIGURED_APPS += system/i2c
|
||||
#CONFIGURED_APPS += tools/i2c_dev
|
||||
CONFIGURED_APPS += systemcmds/i2c
|
||||
|
||||
# Communication and Drivers
|
||||
CONFIGURED_APPS += drivers/boards/px4fmu
|
||||
|
@ -118,6 +125,7 @@ CONFIGURED_APPS += drivers/stm32/adc
|
|||
CONFIGURED_APPS += drivers/px4fmu
|
||||
CONFIGURED_APPS += drivers/hil
|
||||
CONFIGURED_APPS += drivers/gps
|
||||
CONFIGURED_APPS += drivers/mb12xx
|
||||
|
||||
# Testing stuff
|
||||
CONFIGURED_APPS += px4/sensors_bringup
|
||||
|
|
|
@ -369,11 +369,12 @@ CONFIG_I2C_WRITEREAD=y
|
|||
# I2C configuration
|
||||
#
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_POLLED=y
|
||||
CONFIG_I2C_POLLED=n
|
||||
CONFIG_I2C_TRANSFER=y
|
||||
CONFIG_I2C_TRACE=n
|
||||
CONFIG_I2C_RESET=y
|
||||
|
||||
# XXX fixed per-transaction timeout
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
|
||||
|
||||
# XXX re-enable after integration testing
|
||||
|
@ -778,6 +779,7 @@ CONFIG_NXFFS_MAXNAMLEN=32
|
|||
CONFIG_NXFFS_TAILTHRESHOLD=2048
|
||||
CONFIG_NXFFS_PREALLOCATED=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_FS_BINFS=y
|
||||
|
||||
#
|
||||
# SPI-based MMC/SD driver
|
||||
|
|
|
@ -86,7 +86,7 @@ CONFIG_ARCH_BOOTLOADER=n
|
|||
CONFIG_ARCH_LEDS=n
|
||||
CONFIG_ARCH_BUTTONS=n
|
||||
CONFIG_ARCH_CALIBRATION=n
|
||||
CONFIG_ARCH_DMA=n
|
||||
CONFIG_ARCH_DMA=y
|
||||
CONFIG_ARCH_MATH_H=y
|
||||
|
||||
CONFIG_ARMV7M_CMNVECTOR=y
|
||||
|
@ -112,7 +112,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
|
|||
# Individual subsystems can be enabled:
|
||||
#
|
||||
# AHB:
|
||||
CONFIG_STM32_DMA1=n
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=n
|
||||
CONFIG_STM32_CRC=n
|
||||
# APB1:
|
||||
|
@ -189,6 +189,12 @@ CONFIG_USART1_2STOP=0
|
|||
CONFIG_USART2_2STOP=0
|
||||
CONFIG_USART3_2STOP=0
|
||||
|
||||
CONFIG_USART1_RXDMA=y
|
||||
SERIAL_HAVE_CONSOLE_DMA=y
|
||||
# Conflicts with I2C1 DMA
|
||||
CONFIG_USART2_RXDMA=n
|
||||
CONFIG_USART3_RXDMA=y
|
||||
|
||||
#
|
||||
# PX4IO specific driver settings
|
||||
#
|
||||
|
@ -399,7 +405,7 @@ CONFIG_DISABLE_SIGNALS=y
|
|||
CONFIG_DISABLE_MQUEUE=y
|
||||
CONFIG_DISABLE_MOUNTPOINT=y
|
||||
CONFIG_DISABLE_ENVIRON=y
|
||||
CONFIG_DISABLE_POLL=n
|
||||
CONFIG_DISABLE_POLL=y
|
||||
|
||||
#
|
||||
# Misc libc settings
|
||||
|
@ -469,12 +475,12 @@ CONFIG_ARCH_BZERO=n
|
|||
# timer structures to minimize dynamic allocations. Set to
|
||||
# zero for all dynamic allocations.
|
||||
#
|
||||
CONFIG_MAX_TASKS=8
|
||||
CONFIG_MAX_TASKS=4
|
||||
CONFIG_MAX_TASK_ARGS=4
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NPTHREAD_KEYS=2
|
||||
CONFIG_NFILE_DESCRIPTORS=8
|
||||
CONFIG_NFILE_STREAMS=0
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_NAME_MAX=12
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STDIO_LINEBUFFER=n
|
||||
CONFIG_NUNGET_CHARS=2
|
||||
|
@ -535,7 +541,7 @@ CONFIG_BOOT_COPYTORAM=n
|
|||
CONFIG_CUSTOM_STACK=n
|
||||
CONFIG_STACK_POINTER=
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=1200
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=1024
|
||||
CONFIG_HEAP_BASE=
|
||||
|
|
Loading…
Reference in New Issue