Merge remote-tracking branch 'upstream/master' into mtecs

This commit is contained in:
Thomas Gubler
2014-05-28 19:45:20 +02:00
14 changed files with 278 additions and 33 deletions
+13 -12
View File
@@ -14,19 +14,20 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
param set MC_ROLL_P 5.0
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.0
param set MC_PITCH_P 5.0
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.0
param set MC_YAW_P 1.0
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.0
param set MC_ROLL_P 6.0
param set MC_ROLLRATE_P 0.14
param set MC_ROLLRATE_I 0.1
param set MC_ROLLRATE_D 0.002
param set MC_PITCH_P 6.0
param set MC_PITCHRATE_P 0.14
param set MC_PITCHRATE_I 0.1
param set MC_PITCHRATE_D 0.002
param set MC_YAW_P 2.0
param set MC_YAWRATE_P 0.2
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.15
param set MC_YAW_FF 0.8
param set BAT_V_SCALING 0.00838095238
fi
+154
View File
@@ -0,0 +1,154 @@
PX4 mixer definitions
=====================
Files in this directory implement example mixers that can be used as a basis
for customisation, or for general testing purposes.
Mixer basics
------------
Mixers combine control values from various sources (control tasks, user inputs,
etc.) and produce output values suitable for controlling actuators; servos,
motors, switches and so on.
An actuator derives its value from the combination of one or more control
values. Each of the control values is scaled according to the actuator's
configuration and then combined to produce the actuator value, which may then be
further scaled to suit the specific output type.
Internally, all scaling is performed using floating point values. Inputs and
outputs are clamped to the range -1.0 to 1.0.
control control control
| | |
v v v
scale scale scale
| | |
| v |
+-------> mix <------+
|
scale
|
v
out
Scaling
-------
Basic scalers provide linear scaling of the input to the output.
Each scaler allows the input value to be scaled independently for inputs
greater/less than zero. An offset can be applied to the output, and lower and
upper boundary constraints can be applied. Negative scaling factors cause the
output to be inverted (negative input produces positive output).
Scaler pseudocode:
if (input < 0)
output = (input * NEGATIVE_SCALE) + OFFSET
else
output = (input * POSITIVE_SCALE) + OFFSET
if (output < LOWER_LIMIT)
output = LOWER_LIMIT
if (output > UPPER_LIMIT)
output = UPPER_LIMIT
Syntax
------
Mixer definitions are text files; lines beginning with a single capital letter
followed by a colon are significant. All other lines are ignored, meaning that
explanatory text can be freely mixed with the definitions.
Each file may define more than one mixer; the allocation of mixers to actuators
is specific to the device reading the mixer definition, and the number of
actuator outputs generated by a mixer is specific to the mixer.
A mixer begins with a line of the form
<tag>: <mixer arguments>
The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
multirotor mixer, etc.
Null Mixer
..........
A null mixer consumes no controls and generates a single actuator output whose
value is always zero. Typically a null mixer is used as a placeholder in a
collection of mixers in order to achieve a specific pattern of actuator outputs.
The null mixer definition has the form:
Z:
Simple Mixer
............
A simple mixer combines zero or more control inputs into a single actuator
output. Inputs are scaled, and the mixing function sums the result before
applying an output scaler.
A simple mixer definition begins with:
M: <control count>
O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
If <control count> is zero, the sum is effectively zero and the mixer will
output a fixed value that is <offset> constrained by <lower limit> and <upper
limit>.
The second line defines the output scaler with scaler parameters as discussed
above. Whilst the calculations are performed as floating-point operations, the
values stored in the definition file are scaled by a factor of 10000; i.e. an
offset of -0.5 is encoded as -5000.
The definition continues with <control count> entries describing the control
inputs and their scaling, in the form:
S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
The <group> value identifies the control group from which the scaler will read,
and the <index> value an offset within that group. These values are specific to
the device reading the mixer definition.
When used to mix vehicle controls, mixer group zero is the vehicle attitude
control group, and index values zero through three are normally roll, pitch,
yaw and thrust respectively.
The remaining fields on the line configure the control scaler with parameters as
discussed above. Whilst the calculations are performed as floating-point
operations, the values stored in the definition file are scaled by a factor of
10000; i.e. an offset of -0.5 is encoded as -5000.
Multirotor Mixer
................
The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
into a set of actuator outputs intended to drive motor speed controllers.
The mixer definition is a single line of the form:
R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
The supported geometries include:
4x - quadrotor in X configuration
4+ - quadrotor in + configuration
6x - hexcopter in X configuration
6+ - hexcopter in + configuration
8x - octocopter in X configuration
8+ - octocopter in + configuration
Each of the roll, pitch and yaw scale values determine scaling of the roll,
pitch and yaw controls relative to the thrust control. Whilst the calculations
are performed as floating-point operations, the values stored in the definition
file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
range -1.0 to 1.0.
In the case where an actuator saturates, all actuator values are rescaled so that
the saturating actuator is limited to 1.0.
+4 -4
View File
@@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
#
# USART1 Configuration
#
CONFIG_USART1_RXBUFSIZE=256
CONFIG_USART1_TXBUFSIZE=128
CONFIG_USART1_RXBUFSIZE=300
CONFIG_USART1_TXBUFSIZE=300
CONFIG_USART1_BAUD=57600
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0
@@ -528,8 +528,8 @@ CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
CONFIG_UART5_RXBUFSIZE=256
CONFIG_UART5_TXBUFSIZE=128
CONFIG_UART5_RXBUFSIZE=300
CONFIG_UART5_TXBUFSIZE=300
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
+4
View File
@@ -268,6 +268,10 @@
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_1|GPIO_SPEED_50MHz)
#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_1|GPIO_SPEED_50MHz)
/************************************************************************************
* Public Data
************************************************************************************/
+1 -1
View File
@@ -235,7 +235,7 @@ CONFIG_STM32_SDIO=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
# CONFIG_STM32_SPI3 is not set
# CONFIG_STM32_SPI4 is not set
CONFIG_STM32_SPI4=y
# CONFIG_STM32_SPI5 is not set
# CONFIG_STM32_SPI6 is not set
CONFIG_STM32_SYSCFG=y
+2 -1
View File
@@ -86,6 +86,7 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_EXT 2
/*
* Use these in place of the spi_dev_e enumeration to
@@ -98,7 +99,7 @@ __BEGIN_DECLS
/*
* Optional devices on IO's external port
*/
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_ACCEL_MAG 2
/*
* I2C busses
@@ -106,8 +106,11 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_EXT 4
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
@@ -115,6 +118,10 @@ __BEGIN_DECLS
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
/* External bus */
#define PX4_SPIDEV_EXT0 1
#define PX4_SPIDEV_EXT1 2
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_LED 2
@@ -192,6 +192,7 @@ stm32_boardinitialize(void)
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
static struct spi_dev_s *spi4;
static struct sdio_dev_s *sdio;
#include <math.h>
@@ -305,6 +306,17 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
spi4 = up_spiinitialize(4);
/* Default SPI4 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi4, 10000000);
SPI_SETBITS(spi4, 8);
SPI_SETMODE(spi4, SPIDEV_MODE3);
SPI_SELECT(spi4, PX4_SPIDEV_EXT0, false);
SPI_SELECT(spi4, PX4_SPIDEV_EXT1, false);
message("[boot] Initialized SPI port 4\n");
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */
+35
View File
@@ -94,6 +94,13 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_configgpio(GPIO_SPI_CS_FRAM);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
#endif
#ifdef CONFIG_STM32_SPI4
stm32_configgpio(GPIO_SPI_CS_EXT0);
stm32_configgpio(GPIO_SPI_CS_EXT1);
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
#endif
}
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
@@ -157,3 +164,31 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
return SPI_STATUS_PRESENT;
}
#endif
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
switch (devid) {
case PX4_SPIDEV_EXT0:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
break;
case PX4_SPIDEV_EXT1:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
break;
default:
break;
}
}
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
@@ -5,7 +5,7 @@
// Define EKF_DEBUG here to enable the debug print calls
// if the macro is not set, these will be completely
// optimized out by the compiler.
#define EKF_DEBUG
//#define EKF_DEBUG
#ifdef EKF_DEBUG
#include <stdio.h>
+2 -2
View File
@@ -415,7 +415,7 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self)
void
Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self)
{
Mavlink *inst;
LL_FOREACH(_mavlink_instances, inst) {
if (inst != self) {
@@ -886,7 +886,7 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
switch (mavlink_mission_item->command) {
case MAV_CMD_NAV_TAKEOFF:
mission_item->pitch_min = mavlink_mission_item->param2;
mission_item->pitch_min = mavlink_mission_item->param1;
break;
default:
@@ -63,7 +63,7 @@ MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capab
}
bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Init if not done yet */
init();
@@ -76,24 +76,24 @@ bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_
if (isRotarywing)
return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence);
return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence, home_alt);
else
return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence, home_alt);
}
bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
return checkGeofence(dm_current, nMissionItems, geofence);
return (checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Update fixed wing navigation capabilites */
updateNavigationCapabilities();
// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence));
return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
@@ -109,7 +109,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return false;
}
if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) { //xxx: handle relative altitude
if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
return false;
}
@@ -119,6 +119,36 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return true;
}
bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error)
{
/* Check if all all waypoints are above the home altitude, only return false if bool throw_error = true */
for (size_t i = 0; i < nMissionItems; i++) {
static struct mission_item_s missionitem;
const ssize_t len = sizeof(struct mission_item_s);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
if (throw_error) {
return false;
} else {
return true;
}
}
if (home_alt > missionitem.altitude) {
if (throw_error) {
mavlink_log_info(_mavlink_fd, "Waypoint %d below home", i);
return false;
} else {
mavlink_log_info(_mavlink_fd, "#audio: warning waypoint %d below home", i);
return true;
}
}
}
return true;
}
bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems)
{
/* Go through all mission items and search for a landing waypoint
@@ -61,14 +61,15 @@ private:
/* Checks for all airframes */
bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
bool checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error = false);
/* Checks specific to fixedwing airframes */
bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
void updateNavigationCapabilities();
/* Checks specific to rotarywing airframes */
bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
public:
MissionFeasibilityChecker();
@@ -77,7 +78,7 @@ public:
/*
* Returns true if mission is feasible and false otherwise
*/
bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
};
+1 -1
View File
@@ -519,7 +519,7 @@ Navigator::offboard_mission_update(bool isrotaryWing)
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence, _home_pos.alt);
_mission.set_offboard_dataman_id(offboard_mission.dataman_id);