Merge branch 'master' of github.com:PX4/Firmware into indoor

This commit is contained in:
Lorenz Meier
2014-08-27 09:46:21 +02:00
9 changed files with 55 additions and 39 deletions

View File

@@ -8,3 +8,5 @@
sh /etc/init.d/rc.fw_defaults
set MIXER Viper
set FAILSAFE "-c567 -p 1000"

View File

@@ -77,4 +77,9 @@ then
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
fi
fi
if [ $FAILSAFE != none ]
then
pwm failsafe -d $OUTPUT_DEV $FAILSAFE
fi
fi

View File

@@ -66,6 +66,9 @@ then
#
sercon
# Try to get an USB console
nshterm /dev/ttyACM0 &
#
# Start the ORB (first app to start)
#
@@ -96,11 +99,9 @@ then
#
if rgbled start
then
echo "[init] RGB Led"
else
if blinkm start
then
echo "[init] BlinkM"
blinkm systemstate
fi
fi
@@ -129,6 +130,7 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
set FAILSAFE none
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -279,9 +281,6 @@ then
fi
fi
# Try to get an USB console
nshterm /dev/ttyACM0 &
#
# Start the datamanager (and do not abort boot if it fails)
#

View File

@@ -64,21 +64,22 @@ O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
Gimbal / flaps / payload mixer for last four channels
Gimbal / flaps / payload mixer for last four channels,
using the payload control group
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 2 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 2 2 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000
S: 2 3 10000 10000 0 -10000 10000

View File

@@ -52,21 +52,20 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
Gimbal / flaps / payload mixer for last four channels
Inputs to the mixer come from channel group 2 (payload), channels 0
(bay servo 1), 1 (bay servo 2) and 3 (drop release).
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 2 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
S: 2 2 -10000 -10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000

View File

@@ -66,10 +66,10 @@ void CatapultLaunchMethod::update(float accel_x)
last_timestamp = hrt_absolute_time();
if (accel_x > threshold_accel.get()) {
integrator += accel_x * dt;
integrator += dt;
// warnx("*** integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
if (integrator > threshold_accel.get() * threshold_time.get()) {
if (integrator > threshold_time.get()) {
launchDetected = true;
}

View File

@@ -615,6 +615,11 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
case VEHICLE_CMD_PREFLIGHT_STORAGE:
case VEHICLE_CMD_CUSTOM_0:
case VEHICLE_CMD_CUSTOM_1:
case VEHICLE_CMD_CUSTOM_2:
case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
/* ignore commands that handled in low prio loop */
break;

View File

@@ -886,8 +886,8 @@ protected:
msg.eph = cm_uint16_from_m_float(gps.eph);
msg.epv = cm_uint16_from_m_float(gps.epv);
msg.vel = cm_uint16_from_m_float(gps.vel_m_s),
msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
msg.satellites_visible = gps.satellites_used;
msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
msg.satellites_visible = gps.satellites_used;
_mavlink->send_message(MAVLINK_MSG_ID_GPS_RAW_INT, &msg);
}
@@ -957,11 +957,11 @@ protected:
msg.lat = pos.lat * 1e7;
msg.lon = pos.lon * 1e7;
msg.alt = pos.alt * 1000.0f;
msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
msg.vx = pos.vel_n * 100.0f;
msg.vy = pos.vel_e * 100.0f;
msg.vz = pos.vel_d * 100.0f;
msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
msg.vx = pos.vel_n * 100.0f;
msg.vy = pos.vel_e * 100.0f;
msg.vz = pos.vel_d * 100.0f;
msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
_mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, &msg);
}
@@ -1022,9 +1022,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
msg.vx = pos.vx;
msg.vy = pos.vy;
msg.vz = pos.vz;
msg.vx = pos.vx;
msg.vy = pos.vy;
msg.vz = pos.vz;
_mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_NED, &msg);
}
@@ -1085,9 +1085,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
msg.roll = pos.roll;
msg.pitch = pos.pitch;
msg.yaw = pos.yaw;
msg.roll = pos.roll;
msg.pitch = pos.pitch;
msg.yaw = pos.yaw;
_mavlink->send_message(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, &msg);
}

View File

@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* Copyright (C) 2012-2014 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
@@ -37,6 +34,10 @@
/**
* @file vehicle_command.h
* Definition of the vehicle command uORB topic.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_VEHICLE_COMMAND_H_
@@ -52,6 +53,9 @@
* but can contain additional ones.
*/
enum VEHICLE_CMD {
VEHICLE_CMD_CUSTOM_0 = 0, /* test command */
VEHICLE_CMD_CUSTOM_1 = 1, /* test command */
VEHICLE_CMD_CUSTOM_2 = 2, /* test command */
VEHICLE_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
@@ -87,7 +91,8 @@ enum VEHICLE_CMD {
VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
VEHICLE_CMD_ENUM_END = 501, /* | */
VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */
VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */
};
/**
@@ -115,8 +120,8 @@ struct vehicle_command_s {
float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
float param4; /**< Parameter 4, as defined by MAVLink VEHICLE_CMD enum. */
float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
double param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
double param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
enum VEHICLE_CMD command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
uint8_t target_system; /**< System which should execute the command */