forked from Archive/PX4-Autopilot
Merge branch 'release_v1.0.0' into beta
This commit is contained in:
commit
79a690cd17
|
@ -2,6 +2,30 @@
|
|||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MAX 15
|
||||
param set FW_AIRSPD_MIN 10
|
||||
param set FW_AIRSPD_TRIM 13
|
||||
param set FW_ATT_TC 0.3
|
||||
param set FW_L1_DAMPING 0.74
|
||||
param set FW_L1_PERIOD 16
|
||||
param set FW_LND_ANG 15
|
||||
param set FW_LND_FLALT 5
|
||||
param set FW_LND_HHDIST 15
|
||||
param set FW_LND_HVIRT 13
|
||||
param set FW_LND_TLALT 5
|
||||
param set FW_THR_LND_MAX 0
|
||||
param set FW_PR_FF 0.35
|
||||
param set FW_PR_I 0.005
|
||||
param set FW_PR_IMAX 0.4
|
||||
param set FW_PR_P 0.08
|
||||
param set FW_RR_FF 0.6
|
||||
param set FW_RR_I 0.005
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.04
|
||||
fi
|
||||
|
||||
set MIXER Q
|
||||
# Provide ESC a constant 1000 us pulse while disarmed
|
||||
set PWM_OUT 4
|
||||
|
|
|
@ -30,16 +30,6 @@ then
|
|||
param set FW_RR_I 0.005
|
||||
param set FW_RR_IMAX 0.2
|
||||
param set FW_RR_P 0.04
|
||||
param set MT_TKF_PIT_MAX 30.0
|
||||
param set MT_ACC_D 0.2
|
||||
param set MT_ACC_P 0.6
|
||||
param set MT_A_LP 0.5
|
||||
param set MT_PIT_OFF 0.1
|
||||
param set MT_PIT_I 0.1
|
||||
param set MT_THR_OFF 0.65
|
||||
param set MT_THR_I 0.35
|
||||
param set MT_THR_P 0.2
|
||||
param set MT_THR_FF 1.5
|
||||
fi
|
||||
|
||||
set MIXER wingwing
|
||||
|
|
|
@ -34,7 +34,9 @@ then
|
|||
param set PWM_MAIN_REV1 1
|
||||
fi
|
||||
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
set PWM_MIN p:PWM_MIN
|
||||
set PWM_MAX p:PWM_MAX
|
||||
|
||||
set MIXER caipi
|
||||
# Provide ESC a constant 1000 us pulse
|
||||
set PWM_OUT 4
|
||||
set PWM_DISARMED 1000
|
||||
set PWM_OUT 1234
|
||||
|
|
|
@ -10,11 +10,11 @@ sh /etc/init.d/4001_quad_x
|
|||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_P 0.13
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_P 0.13
|
||||
param set MC_PITCHRATE_I 0.05
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
|
|
|
@ -11,15 +11,15 @@ if [ $AUTOCNF == yes ]
|
|||
then
|
||||
# TODO REVIEW
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_P 0.16
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_ROLLRATE_D 0.01
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_P 0.16
|
||||
param set MC_PITCHRATE_I 0.05
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_PITCHRATE_D 0.01
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
|
|
@ -9,18 +9,17 @@ sh /etc/init.d/4001_quad_x
|
|||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
# TODO REVIEW
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_P 0.16
|
||||
param set MC_ROLLRATE_I 0.05
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_ROLLRATE_D 0.01
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_P 0.16
|
||||
param set MC_PITCHRATE_I 0.05
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_PITCHRATE_D 0.01
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.0
|
||||
param set MC_YAWRATE_P 0.3
|
||||
param set MC_YAWRATE_I 0.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
fi
|
||||
|
||||
|
|
|
@ -4,38 +4,6 @@ set VEHICLE_TYPE mc
|
|||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set MC_ROLL_P 7.0
|
||||
param set MC_ROLLRATE_P 0.1
|
||||
param set MC_ROLLRATE_I 0.0
|
||||
param set MC_ROLLRATE_D 0.003
|
||||
param set MC_PITCH_P 7.0
|
||||
param set MC_PITCHRATE_P 0.1
|
||||
param set MC_PITCHRATE_I 0.0
|
||||
param set MC_PITCHRATE_D 0.003
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.2
|
||||
param set MC_YAWRATE_I 0.1
|
||||
param set MC_YAWRATE_D 0.0
|
||||
param set MC_YAW_FF 0.5
|
||||
|
||||
param set MPC_THR_MAX 1.0
|
||||
param set MPC_THR_MIN 0.1
|
||||
param set MPC_XY_P 1.0
|
||||
param set MPC_XY_VEL_P 0.1
|
||||
param set MPC_XY_VEL_I 0.02
|
||||
param set MPC_XY_VEL_D 0.01
|
||||
param set MPC_XY_VEL_MAX 5
|
||||
param set MPC_XY_FF 0.5
|
||||
param set MPC_Z_P 1.0
|
||||
param set MPC_Z_VEL_P 0.1
|
||||
param set MPC_Z_VEL_I 0.02
|
||||
param set MPC_Z_VEL_D 0.0
|
||||
param set MPC_Z_VEL_MAX 3
|
||||
param set MPC_Z_FF 0.5
|
||||
param set MPC_TILTMAX_AIR 45.0
|
||||
param set MPC_TILTMAX_LND 15.0
|
||||
param set MPC_LAND_SPEED 1.0
|
||||
|
||||
param set PE_VELNE_NOISE 0.5
|
||||
param set PE_VELD_NOISE 0.7
|
||||
param set PE_POSNE_NOISE 0.5
|
||||
|
|
|
@ -3,21 +3,21 @@
|
|||
# USB MAVLink start
|
||||
#
|
||||
|
||||
mavlink start -r 80000 -d /dev/ttyACM0 -x
|
||||
mavlink start -r 800000 -d /dev/ttyACM0 -x
|
||||
# Enable a number of interesting streams we want via USB
|
||||
mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 300
|
||||
mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50
|
||||
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
|
||||
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW_RAD -r 10
|
||||
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
|
||||
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
|
||||
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 100
|
||||
mavlink stream -d /dev/ttyACM0 -s ACTUATOR_CONTROL_TARGET0 -r 30
|
||||
mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
|
||||
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
|
||||
mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
|
||||
mavlink stream -d /dev/ttyACM0 -s LOCAL_POSITION_NED -r 30
|
||||
mavlink stream -d /dev/ttyACM0 -s MANUAL_CONTROL -r 5
|
||||
mavlink stream -d /dev/ttyACM0 -s HIGHRES_IMU -r 20
|
||||
mavlink stream -d /dev/ttyACM0 -s HIGHRES_IMU -r 100
|
||||
mavlink stream -d /dev/ttyACM0 -s GPS_RAW_INT -r 20
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
|
|
|
@ -479,11 +479,11 @@ then
|
|||
# but this works for now
|
||||
if param compare SYS_COMPANION 921600
|
||||
then
|
||||
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 20000
|
||||
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 20000 -x
|
||||
fi
|
||||
if param compare SYS_COMPANION 57600
|
||||
then
|
||||
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 1000
|
||||
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 1000 -x
|
||||
fi
|
||||
if param compare SYS_COMPANION 157600
|
||||
then
|
||||
|
|
|
@ -83,7 +83,7 @@ __BEGIN_DECLS
|
|||
/**
|
||||
* Highest maximum PWM in us
|
||||
*/
|
||||
#define PWM_HIGHEST_MAX 2100
|
||||
#define PWM_HIGHEST_MAX 2150
|
||||
|
||||
/**
|
||||
* Default maximum PWM in us
|
||||
|
|
|
@ -794,7 +794,7 @@ start(void)
|
|||
sem_init(&g_init_sema, 1, 0);
|
||||
|
||||
/* start the worker thread */
|
||||
if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1800, task_main, NULL)) <= 0) {
|
||||
if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1500, task_main, NULL)) <= 0) {
|
||||
warn("task start failed");
|
||||
return -1;
|
||||
}
|
||||
|
|
|
@ -85,12 +85,12 @@ bool FixedwingLandDetector::update()
|
|||
bool landDetected = false;
|
||||
|
||||
if (hrt_elapsed_time(&_vehicleLocalPosition.timestamp) < 500 * 1000) {
|
||||
float val = 0.95f * _velocity_xy_filtered + 0.05f * sqrtf(_vehicleLocalPosition.vx *
|
||||
float val = 0.97f * _velocity_xy_filtered + 0.03f * sqrtf(_vehicleLocalPosition.vx *
|
||||
_vehicleLocalPosition.vx + _vehicleLocalPosition.vy * _vehicleLocalPosition.vy);
|
||||
if (isfinite(val)) {
|
||||
_velocity_xy_filtered = val;
|
||||
}
|
||||
val = 0.95f * _velocity_z_filtered + 0.05f * fabsf(_vehicleLocalPosition.vz);
|
||||
val = 0.99f * _velocity_z_filtered + 0.01f * fabsf(_vehicleLocalPosition.vz);
|
||||
|
||||
if (isfinite(val)) {
|
||||
_velocity_z_filtered = val;
|
||||
|
|
|
@ -96,7 +96,7 @@ PARAM_DEFINE_FLOAT(LNDMC_THR_MAX, 0.20f);
|
|||
*
|
||||
* @group Land Detector
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 4.0f);
|
||||
PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Fixedwing max climb rate
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 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
|
||||
|
@ -36,6 +36,7 @@
|
|||
* Mavlink parameters manager implementation.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
@ -130,7 +131,17 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
|
||||
} else {
|
||||
/* when index is >= 0, send this parameter again */
|
||||
send_param(param_for_used_index(req_read.param_index));
|
||||
int ret = send_param(param_for_used_index(req_read.param_index));
|
||||
|
||||
if (ret == 1) {
|
||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||
sprintf(buf, "[pm] unknown param ID: %u", req_read.param_index);
|
||||
_mavlink->send_statustext_info(buf);
|
||||
} else if (ret == 2) {
|
||||
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
|
||||
sprintf(buf, "[pm] failed loading param from storage ID: %u", req_read.param_index);
|
||||
_mavlink->send_statustext_info(buf);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -207,11 +218,11 @@ MavlinkParametersManager::send(const hrt_abstime t)
|
|||
}
|
||||
}
|
||||
|
||||
void
|
||||
int
|
||||
MavlinkParametersManager::send_param(param_t param)
|
||||
{
|
||||
if (param == PARAM_INVALID) {
|
||||
return;
|
||||
return 1;
|
||||
}
|
||||
|
||||
mavlink_param_value_t msg;
|
||||
|
@ -221,7 +232,7 @@ MavlinkParametersManager::send_param(param_t param)
|
|||
* space during transmission, copy param onto float val_buf
|
||||
*/
|
||||
if (param_get(param, &msg.param_value) != OK) {
|
||||
return;
|
||||
return 2;
|
||||
}
|
||||
|
||||
msg.param_count = param_count_used();
|
||||
|
@ -248,4 +259,6 @@ MavlinkParametersManager::send_param(param_t param)
|
|||
}
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_PARAM_VALUE, &msg);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-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
|
||||
|
@ -36,6 +36,7 @@
|
|||
* Mavlink parameters manager definition.
|
||||
*
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -113,7 +114,7 @@ protected:
|
|||
|
||||
void send(const hrt_abstime t);
|
||||
|
||||
void send_param(param_t param);
|
||||
int send_param(param_t param);
|
||||
|
||||
orb_advert_t _rc_param_map_pub;
|
||||
struct rc_parameter_map_s _rc_param_map;
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.5f);
|
||||
|
||||
/**
|
||||
* Roll rate P gain
|
||||
|
@ -60,7 +60,7 @@ PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.12f);
|
||||
|
||||
/**
|
||||
* Roll rate I gain
|
||||
|
@ -70,7 +70,7 @@ PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.05f);
|
||||
|
||||
/**
|
||||
* Roll rate D gain
|
||||
|
@ -80,7 +80,7 @@ PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.002f);
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.003f);
|
||||
|
||||
/**
|
||||
* Roll rate feedforward
|
||||
|
@ -101,7 +101,7 @@ PARAM_DEFINE_FLOAT(MC_ROLLRATE_FF, 0.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.5f);
|
||||
|
||||
/**
|
||||
* Pitch rate P gain
|
||||
|
@ -111,7 +111,7 @@ PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.12f);
|
||||
|
||||
/**
|
||||
* Pitch rate I gain
|
||||
|
@ -121,7 +121,7 @@ PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.05f);
|
||||
|
||||
/**
|
||||
* Pitch rate D gain
|
||||
|
@ -131,7 +131,7 @@ PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.002f);
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.003f);
|
||||
|
||||
/**
|
||||
* Pitch rate feedforward
|
||||
|
@ -152,7 +152,7 @@ PARAM_DEFINE_FLOAT(MC_PITCHRATE_FF, 0.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAW_P, 2.8f);
|
||||
|
||||
/**
|
||||
* Yaw rate P gain
|
||||
|
@ -162,7 +162,7 @@ PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.2f);
|
||||
|
||||
/**
|
||||
* Yaw rate I gain
|
||||
|
@ -172,7 +172,7 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
|
|||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.1f);
|
||||
|
||||
/**
|
||||
* Yaw rate D gain
|
||||
|
|
|
@ -107,9 +107,10 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
|
|||
*
|
||||
* @unit m/s
|
||||
* @min 0.0
|
||||
* @max 8 m/s
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 3.0f);
|
||||
|
||||
/**
|
||||
* Vertical velocity feed forward
|
||||
|
|
|
@ -521,7 +521,7 @@ Navigator::start()
|
|||
_navigator_task = task_spawn_cmd("navigator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 20,
|
||||
1700,
|
||||
1500,
|
||||
(main_t)&Navigator::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
|
|
@ -1401,3 +1401,110 @@ PARAM_DEFINE_INT32(RC_RSSI_PWM_MAX, 1000);
|
|||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
|
||||
|
||||
/**
|
||||
* Enable Lidar-Lite (LL40LS) pwm driver
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Sensor Enable
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 1000 for default or 900 to increase servo travel
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MIN, 1000);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 2000 for default or 2100 to increase servo travel
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAX, 2000);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* The main use of this parameter is to silence ESCs when they are disarmed.
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_DISARMED, 0);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 1000 for default or 900 to increase servo travel
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 2000 for default or 2100 to increase servo travel
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for AUX outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* The main use of this parameter is to silence ESCs when they are disarmed.
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DISARMED, 1000);
|
||||
|
|
|
@ -634,6 +634,12 @@ Sensors::Sensors() :
|
|||
(void)param_find("CAL_MAG2_ROT");
|
||||
(void)param_find("SYS_PARAM_VER");
|
||||
(void)param_find("SYS_AUTOSTART");
|
||||
(void)param_find("PWM_MIN");
|
||||
(void)param_find("PWM_MAX");
|
||||
(void)param_find("PWM_DISARMED");
|
||||
(void)param_find("PWM_AUX_MIN");
|
||||
(void)param_find("PWM_AUX_MAX");
|
||||
(void)param_find("PWM_AUX_DISARMED");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
|
|
|
@ -55,8 +55,7 @@ SRCS = err.c \
|
|||
pwm_limit/pwm_limit.c \
|
||||
circuit_breaker.cpp \
|
||||
circuit_breaker_params.c \
|
||||
mcu_version.c \
|
||||
circuit_breaker_params.c
|
||||
mcu_version.c
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
|
|
|
@ -189,7 +189,7 @@ param_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
|
||||
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'");
|
||||
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare',\n'index', 'index_used', 'select' or 'save'");
|
||||
}
|
||||
|
||||
static void
|
||||
|
|
|
@ -59,6 +59,7 @@
|
|||
|
||||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/err.h"
|
||||
#include "systemlib/param/param.h"
|
||||
#include "drivers/drv_pwm_output.h"
|
||||
|
||||
static void usage(const char *reason);
|
||||
|
@ -187,10 +188,35 @@ pwm_main(int argc, char *argv[])
|
|||
break;
|
||||
|
||||
case 'p':
|
||||
pwm_value = strtoul(optarg, &ep, 0);
|
||||
{
|
||||
/* check if this is a param name */
|
||||
if (strncmp("p:", optarg, 2) == 0) {
|
||||
|
||||
if (*ep != '\0') {
|
||||
usage("BAD PWM VAL");
|
||||
char buf[32];
|
||||
strncpy(buf, optarg + 2, 16);
|
||||
/* user wants to use a param name */
|
||||
param_t parm = param_find(buf);
|
||||
|
||||
if (parm != PARAM_INVALID) {
|
||||
int32_t pwm_parm;
|
||||
int gret = param_get(parm, &pwm_parm);
|
||||
|
||||
if (gret == 0) {
|
||||
pwm_value = pwm_parm;
|
||||
} else {
|
||||
usage("PARAM LOAD FAIL");
|
||||
}
|
||||
} else {
|
||||
usage("PARAM NAME NOT FOUND");
|
||||
}
|
||||
} else {
|
||||
|
||||
pwm_value = strtoul(optarg, &ep, 0);
|
||||
}
|
||||
|
||||
if (*ep != '\0') {
|
||||
usage("BAD PWM VAL");
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue