Browse Source

Merge branch 'release_v1.0.0' of github.com:PX4/Firmware into beta

sbg
Lorenz Meier 10 years ago
parent
commit
93d3eb1b4c
  1. 4
      ROMFS/px4fmu_common/init.d/rc.fw_defaults
  2. 4
      ROMFS/px4fmu_common/init.d/rc.mc_defaults
  3. 4
      ROMFS/px4fmu_common/init.d/rc.vtol_defaults
  4. 2
      makefiles/upload.mk
  5. 10
      src/drivers/l3gd20/l3gd20.cpp
  6. 7
      src/modules/commander/commander_params.c
  7. 20
      src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
  8. 9
      src/modules/mavlink/mavlink.c
  9. 4
      src/modules/mavlink/mavlink_messages.cpp
  10. 26
      src/modules/mc_pos_control/mc_pos_control_main.cpp
  11. 15
      src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp
  12. 13
      src/modules/navigator/datalinkloss_params.c
  13. 9
      src/modules/position_estimator_inav/position_estimator_inav_main.c
  14. 1019
      src/modules/sensors/sensor_params.c
  15. 26
      src/modules/vtol_att_control/vtol_att_control_params.c

4
ROMFS/px4fmu_common/init.d/rc.fw_defaults

@ -17,9 +17,9 @@ then @@ -17,9 +17,9 @@ then
param set FW_T_TIME_CONST 5
param set PE_VELNE_NOISE 0.3
param set PE_VELD_NOISE 0.5
param set PE_VELD_NOISE 0.35
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 0.5
param set PE_POSD_NOISE 1.0
param set PE_GBIAS_PNOISE 0.000001
param set PE_ABIAS_PNOISE 0.0002
fi

4
ROMFS/px4fmu_common/init.d/rc.mc_defaults

@ -5,9 +5,9 @@ set VEHICLE_TYPE mc @@ -5,9 +5,9 @@ set VEHICLE_TYPE mc
if [ $AUTOCNF == yes ]
then
param set PE_VELNE_NOISE 0.5
param set PE_VELD_NOISE 0.7
param set PE_VELD_NOISE 0.35
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
param set PE_POSD_NOISE 1.25
param set PE_GBIAS_PNOISE 0.000001
param set PE_ABIAS_PNOISE 0.0001

4
ROMFS/px4fmu_common/init.d/rc.vtol_defaults

@ -34,9 +34,9 @@ then @@ -34,9 +34,9 @@ then
param set FW_RR_P 0.02
param set PE_VELNE_NOISE 0.5
param set PE_VELD_NOISE 0.7
param set PE_VELD_NOISE 0.3
param set PE_POSNE_NOISE 0.5
param set PE_POSD_NOISE 1.0
param set PE_POSD_NOISE 1.25
param set PE_GBIAS_PNOISE 0.000001
param set PE_ABIAS_PNOISE 0.0001
fi

2
makefiles/upload.mk

@ -15,7 +15,7 @@ ifeq ($(SYSTYPE),Darwin) @@ -15,7 +15,7 @@ ifeq ($(SYSTYPE),Darwin)
SERIAL_PORTS ?= "/dev/tty.usbmodemPX*,/dev/tty.usbmodem*"
endif
ifeq ($(SYSTYPE),Linux)
SERIAL_PORTS ?= "/dev/serial/by-id/usb-3D_Robotics*"
SERIAL_PORTS ?= "/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/pci-3D_Robotics*"
endif
ifeq ($(SERIAL_PORTS),)
SERIAL_PORTS = "COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0"

10
src/drivers/l3gd20/l3gd20.cpp

@ -179,6 +179,8 @@ static const int ERROR = -1; @@ -179,6 +179,8 @@ static const int ERROR = -1;
#define L3GD20_DEFAULT_FILTER_FREQ 30
#define L3GD20_TEMP_OFFSET_CELSIUS 40
#define L3GD20_MAX_OFFSET 0.45f /**< max offset: 25 degrees/s */
#ifdef PX4_SPI_BUS_EXT
#define EXTERNAL_BUS PX4_SPI_BUS_EXT
#else
@ -1102,18 +1104,18 @@ L3GD20::test_error() @@ -1102,18 +1104,18 @@ L3GD20::test_error()
int
L3GD20::self_test()
{
/* evaluate gyro offsets, complain if offset -> zero or larger than 6 dps */
if (fabsf(_gyro_scale.x_offset) > 0.1f || fabsf(_gyro_scale.x_offset) < 0.000001f)
/* evaluate gyro offsets, complain if offset -> zero or larger than 25 dps */
if (fabsf(_gyro_scale.x_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.x_offset) < 0.000001f)
return 1;
if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f)
return 1;
if (fabsf(_gyro_scale.y_offset) > 0.1f || fabsf(_gyro_scale.y_offset) < 0.000001f)
if (fabsf(_gyro_scale.y_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.y_offset) < 0.000001f)
return 1;
if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f)
return 1;
if (fabsf(_gyro_scale.z_offset) > 0.1f || fabsf(_gyro_scale.z_offset) < 0.000001f)
if (fabsf(_gyro_scale.z_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.z_offset) < 0.000001f)
return 1;
if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f)
return 1;

7
src/modules/commander/commander_params.c

@ -150,11 +150,12 @@ PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f); @@ -150,11 +150,12 @@ PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f);
/**
* Engine Failure Current/Throttle Threshold
*
* Engine failure triggers only below this current/throttle value
* Engine failure triggers only below this current value
*
* @group Commander
* @min 0.0
* @max 7.0
* @max 30.0
* @unit ampere
*/
PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
@ -167,7 +168,7 @@ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f); @@ -167,7 +168,7 @@ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
* @group Commander
* @unit second
* @min 0.0
* @max 7.0
* @max 60.0
*/
PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f);

20
src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c

@ -141,13 +141,13 @@ PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f); @@ -141,13 +141,13 @@ PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f);
/**
* Velocity noise in down (vertical) direction
*
* Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7
* Generic default: 0.3, multicopters: 0.4, ground vehicles: 0.7
*
* @min 0.05
* @max 5.0
* @min 0.2
* @max 3.0
* @group Position Estimator
*/
PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.5f);
PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.3f);
/**
* Position noise in north-east (horizontal) direction
@ -163,21 +163,21 @@ PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f); @@ -163,21 +163,21 @@ PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f);
/**
* Position noise in down (vertical) direction
*
* Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0
* Generic defaults: 1.25, multicopters: 1.0, ground vehicles: 1.0
*
* @min 0.1
* @max 10.0
* @min 0.5
* @max 3.0
* @group Position Estimator
*/
PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 0.5f);
PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 1.25f);
/**
* Magnetometer measurement noise
*
* Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05
*
* @min 0.1
* @max 10.0
* @min 0.01
* @max 1.0
* @group Position Estimator
*/
PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f);

9
src/modules/mavlink/mavlink.c

@ -59,15 +59,18 @@ PARAM_DEFINE_INT32(MAV_SYS_ID, 1); @@ -59,15 +59,18 @@ PARAM_DEFINE_INT32(MAV_SYS_ID, 1);
* MAVLink component ID
* @group MAVLink
* @min 1
* @max 50
* @max 250
*/
PARAM_DEFINE_INT32(MAV_COMP_ID, 50);
/**
* MAVLink type
* MAVLink airframe type
*
*
* @min 0
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
PARAM_DEFINE_INT32(MAV_TYPE, 1);
/**
* Use/Accept HIL GPS message (even if not in HIL mode)

4
src/modules/mavlink/mavlink_messages.cpp

@ -1767,6 +1767,10 @@ protected: @@ -1767,6 +1767,10 @@ protected:
msg.x = pos_sp.x;
msg.y = pos_sp.y;
msg.z = pos_sp.z;
msg.yaw = pos_sp.yaw;
msg.vx = pos_sp.vx;
msg.vy = pos_sp.vy;
msg.vz = pos_sp.vz;
_mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, &msg);
}

26
src/modules/mc_pos_control/mc_pos_control_main.cpp

@ -1380,44 +1380,44 @@ MulticopterPositionControl::task_main() @@ -1380,44 +1380,44 @@ MulticopterPositionControl::task_main()
reset_int_xy = true;
}
// generate attitude setpoint from manual controls
/* generate attitude setpoint from manual controls */
if(_control_mode.flag_control_manual_enabled && _control_mode.flag_control_attitude_enabled) {
// reset yaw setpoint to current position if needed
/* reset yaw setpoint to current position if needed */
if (reset_yaw_sp) {
reset_yaw_sp = false;
_att_sp.yaw_body = _att.yaw;
}
// do not move yaw while arming
/* do not move yaw while arming */
else if (_manual.z > 0.1f)
{
const float YAW_OFFSET_MAX = _params.man_yaw_max / _params.mc_att_yaw_p;
const float yaw_offset_max = _params.man_yaw_max / _params.mc_att_yaw_p;
_att_sp.yaw_sp_move_rate = _manual.r * _params.man_yaw_max;
_att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + _att_sp.yaw_sp_move_rate * dt);
float yaw_offs = _wrap_pi(_att_sp.yaw_body - _att.yaw);
if (yaw_offs < - YAW_OFFSET_MAX) {
_att_sp.yaw_body = _wrap_pi(_att.yaw - YAW_OFFSET_MAX);
float yaw_target = _wrap_pi(_att_sp.yaw_body + _att_sp.yaw_sp_move_rate * dt);
float yaw_offs = _wrap_pi(yaw_target - _att.yaw);
} else if (yaw_offs > YAW_OFFSET_MAX) {
_att_sp.yaw_body = _wrap_pi(_att.yaw + YAW_OFFSET_MAX);
// If the yaw offset became too big for the system to track stop
// shifting it
if (fabsf(yaw_offs) < yaw_offset_max) {
_att_sp.yaw_body = yaw_target;
}
}
//Control roll and pitch directly if we no aiding velocity controller is active
/* control roll and pitch directly if we no aiding velocity controller is active */
if (!_control_mode.flag_control_velocity_enabled) {
_att_sp.roll_body = _manual.y * _params.man_roll_max;
_att_sp.pitch_body = -_manual.x * _params.man_pitch_max;
}
//Control climb rate directly if no aiding altitude controller is active
/* control throttle directly if no climb rate controller is active */
if (!_control_mode.flag_control_climb_rate_enabled) {
_att_sp.thrust = math::min(_manual.z, _params.thr_max);
_att_sp.thrust = math::max(_att_sp.thrust, _params.thr_min);
}
//Construct attitude setpoint rotation matrix
/* construct attitude setpoint rotation matrix */
math::Matrix<3,3> R_sp;
R_sp.from_euler(_att_sp.roll_body,_att_sp.pitch_body,_att_sp.yaw_body);
memcpy(&_att_sp.R_body[0], R_sp.data, sizeof(_att_sp.R_body));

15
src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp

@ -647,6 +647,21 @@ void MulticopterPositionControl::handle_vehicle_attitude(const px4_vehicle_atti @@ -647,6 +647,21 @@ void MulticopterPositionControl::handle_vehicle_attitude(const px4_vehicle_atti
_vel_sp = pos_err.emult(_params.pos_p) + _vel_ff;
/* make sure velocity setpoint is saturated in xy*/
float vel_norm_xy = sqrtf(_vel_sp(0)*_vel_sp(0) +
_vel_sp(1)*_vel_sp(1));
if (vel_norm_xy > _params.vel_max(0)) {
/* note assumes vel_max(0) == vel_max(1) */
_vel_sp(0) = _vel_sp(0)*_params.vel_max(0)/vel_norm_xy;
_vel_sp(1) = _vel_sp(1)*_params.vel_max(1)/vel_norm_xy;
}
/* make sure velocity setpoint is saturated in z*/
float vel_norm_z = sqrtf(_vel_sp(2)*_vel_sp(2));
if (vel_norm_z > _params.vel_max(2)) {
_vel_sp(2) = _vel_sp(2)*_params.vel_max(2)/vel_norm_z;
}
if (!_control_mode->data().flag_control_altitude_enabled) {
_reset_alt_sp = true;
_vel_sp(2) = 0.0f;

13
src/modules/navigator/datalinkloss_params.c

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
* Copyright (c) 2014, 2015 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
@ -64,7 +64,8 @@ PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f); @@ -64,7 +64,8 @@ PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f);
* Latitude of comms hold waypoint
*
* @unit degrees * 1e7
* @min 0
* @min -90
* @max 90
* @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
@ -75,7 +76,8 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120); @@ -75,7 +76,8 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
* Longitude of comms hold waypoint
*
* @unit degrees * 1e7
* @min 0
* @min -180
* @max 180
* @group Data Link Loss
*/
PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
@ -86,13 +88,14 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890); @@ -86,13 +88,14 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
* Altitude of comms hold waypoint
*
* @unit m
* @min 0.0
* @min -50
* @max 30000
* @group Data Link Loss
*/
PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f);
/**
* Aifield hole wait time
* Airfield hole wait time
*
* The amount of time in seconds the system should wait at the airfield home waypoint
*

9
src/modules/position_estimator_inav/position_estimator_inav_main.c

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013, 2014 PX4 Development Team. All rights reserved.
* Copyright (c) 2013-2015 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
@ -147,10 +147,9 @@ int position_estimator_inav_main(int argc, char *argv[]) @@ -147,10 +147,9 @@ int position_estimator_inav_main(int argc, char *argv[])
verbose_mode = false;
if (argc > 1)
if (!strcmp(argv[2], "-v")) {
verbose_mode = true;
}
if (argc > 2 && !strcmp(argv[2], "-v")) {
verbose_mode = true;
}
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",

1019
src/modules/sensors/sensor_params.c

File diff suppressed because it is too large Load Diff

26
src/modules/vtol_att_control/vtol_att_control_params.c

@ -43,10 +43,10 @@ @@ -43,10 +43,10 @@
/**
* VTOL number of engines
*
* @min 1
* @min 0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_MOT_COUNT,0);
PARAM_DEFINE_INT32(VT_MOT_COUNT, 0);
/**
* Idle speed of VTOL when in multicopter mode
@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(VT_MOT_COUNT,0); @@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(VT_MOT_COUNT,0);
* @min 900
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900);
PARAM_DEFINE_INT32(VT_IDLE_PWM_MC, 900);
/**
* Minimum airspeed in multicopter mode
@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900); @@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900);
* @min 0.0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f);
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN, 10.0f);
/**
* Maximum airspeed in multicopter mode
@ -74,7 +74,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f); @@ -74,7 +74,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f);
* @min 0.0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f);
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX, 30.0f);
/**
* Trim airspeed when in multicopter mode
@ -84,7 +84,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f); @@ -84,7 +84,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f);
* @min 0.0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f);
PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM, 10.0f);
/**
* Permanent stabilization in fw mode
@ -96,7 +96,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f); @@ -96,7 +96,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f);
* @max 1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0);
PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0);
/**
* Fixed wing pitch trim
@ -107,7 +107,7 @@ PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0); @@ -107,7 +107,7 @@ PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0);
* @max 1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f);
PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM, 0.0f);
/**
* Motor max power
@ -118,18 +118,18 @@ PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f); @@ -118,18 +118,18 @@ PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f);
* @min 1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_POWER_MAX,120.0f);
PARAM_DEFINE_FLOAT(VT_POWER_MAX, 120.0f);
/**
* Propeller efficiency parameter
*
* Influences propeller efficiency at different power settings. Should be tuned beforehand.
*
* @min 0.5
* @min 0.0
* @max 0.9
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f);
PARAM_DEFINE_FLOAT(VT_PROP_EFF, 0.0f);
/**
* Total airspeed estimate low-pass filter gain
@ -140,7 +140,7 @@ PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f); @@ -140,7 +140,7 @@ PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f);
* @max 0.99
* @group VTOL Attitude Control
*/
PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN,0.3f);
PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN, 0.3f);
/**
* VTOL Type (Tailsitter=0, Tiltrotor=1)
@ -160,4 +160,4 @@ PARAM_DEFINE_INT32(VT_TYPE, 0); @@ -160,4 +160,4 @@ PARAM_DEFINE_INT32(VT_TYPE, 0);
* @max 1
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK,0);
PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0);

Loading…
Cancel
Save