forked from Archive/PX4-Autopilot
Merge branch 'beta' of github.com:PX4/Firmware into paul_estimator
This commit is contained in:
commit
87410b5bde
Binary file not shown.
|
@ -1,88 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script for logging purposes
|
||||
#
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Start sensor drivers here.
|
||||
#
|
||||
|
||||
ms5611 start
|
||||
adc start
|
||||
|
||||
# mag might be external
|
||||
if hmc5883 start
|
||||
then
|
||||
echo "using HMC5883"
|
||||
fi
|
||||
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "using MPU6000"
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "using L3GD20(H)"
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
set BOARD fmuv2
|
||||
else
|
||||
set BOARD fmuv1
|
||||
fi
|
||||
|
||||
# Start airspeed sensors
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "using MEAS airspeed sensor"
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
echo "using ETS airspeed sensor (bus 3)"
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
echo "Using ETS airspeed sensor (bus 1)"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensor collection task.
|
||||
# IMPORTANT: this also loads param offsets
|
||||
# ALWAYS start this task before the
|
||||
# preflight_check.
|
||||
#
|
||||
if sensors start
|
||||
then
|
||||
echo "SENSORS STARTED"
|
||||
fi
|
||||
|
||||
sdlog2 start -r 250 -e -b 16
|
||||
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
Binary file not shown.
|
@ -160,7 +160,7 @@ ORB_DECLARE(output_pwm);
|
|||
|
||||
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
|
||||
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
|
||||
#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
|
||||
#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
|
||||
|
||||
/** power up DSM receiver */
|
||||
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
|
||||
|
|
|
@ -705,7 +705,7 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C)
|
|||
Motor[i].State |= MOTOR_STATE_PRESENT_MASK; // set present bit;
|
||||
foundMotorCount++;
|
||||
|
||||
if (Motor[i].MaxPWM == 250) {
|
||||
if ((Motor[i].MaxPWM & 252) == 248) {
|
||||
Motor[i].Version = BLCTRL_NEW;
|
||||
|
||||
} else {
|
||||
|
|
|
@ -244,8 +244,7 @@ private:
|
|||
volatile int _task; ///< worker task id
|
||||
volatile bool _task_should_exit; ///< worker terminate flag
|
||||
|
||||
int _mavlink_fd; ///< mavlink file descriptor. This is opened by class instantiation and Doesn't appear to be usable in main thread.
|
||||
int _thread_mavlink_fd; ///< mavlink file descriptor for thread.
|
||||
int _mavlink_fd; ///< mavlink file descriptor.
|
||||
|
||||
perf_counter_t _perf_update; ///<local performance counter for status updates
|
||||
perf_counter_t _perf_write; ///<local performance counter for PWM control writes
|
||||
|
@ -474,7 +473,6 @@ PX4IO::PX4IO(device::Device *interface) :
|
|||
_task(-1),
|
||||
_task_should_exit(false),
|
||||
_mavlink_fd(-1),
|
||||
_thread_mavlink_fd(-1),
|
||||
_perf_update(perf_alloc(PC_ELAPSED, "io update")),
|
||||
_perf_write(perf_alloc(PC_ELAPSED, "io write")),
|
||||
_perf_chan_count(perf_alloc(PC_COUNT, "io rc #")),
|
||||
|
@ -507,9 +505,6 @@ PX4IO::PX4IO(device::Device *interface) :
|
|||
/* we need this potentially before it could be set in task_main */
|
||||
g_dev = this;
|
||||
|
||||
/* open MAVLink text channel */
|
||||
_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
_debug_enabled = false;
|
||||
_servorail_status.rssi_v = 0;
|
||||
}
|
||||
|
@ -785,7 +780,7 @@ PX4IO::task_main()
|
|||
hrt_abstime poll_last = 0;
|
||||
hrt_abstime orb_check_last = 0;
|
||||
|
||||
_thread_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
|
||||
_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
/*
|
||||
* Subscribe to the appropriate PWM output topic based on whether we are the
|
||||
|
@ -880,6 +875,10 @@ PX4IO::task_main()
|
|||
/* run at 5Hz */
|
||||
orb_check_last = now;
|
||||
|
||||
/* try to claim the MAVLink log FD */
|
||||
if (_mavlink_fd < 0)
|
||||
_mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
/* check updates on uORB topics and handle it */
|
||||
bool updated = false;
|
||||
|
||||
|
@ -1275,16 +1274,14 @@ void
|
|||
PX4IO::dsm_bind_ioctl(int dsmMode)
|
||||
{
|
||||
if (!(_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
|
||||
/* 0: dsm2, 1:dsmx */
|
||||
if ((dsmMode == 0) || (dsmMode == 1)) {
|
||||
mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%s rx", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "x" : "x8"));
|
||||
ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
|
||||
} else {
|
||||
mavlink_log_info(_thread_mavlink_fd, "[IO] invalid dsm bind mode, bind request rejected");
|
||||
}
|
||||
mavlink_log_info(_mavlink_fd, "[IO] binding DSM%s RX", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "-X" : "-X8"));
|
||||
int ret = ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
|
||||
|
||||
if (ret)
|
||||
mavlink_log_critical(_mavlink_fd, "binding failed.");
|
||||
|
||||
} else {
|
||||
mavlink_log_info(_thread_mavlink_fd, "[IO] system armed, bind request rejected");
|
||||
mavlink_log_info(_mavlink_fd, "[IO] system armed, bind request rejected");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2115,14 +2112,24 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
|
|||
break;
|
||||
|
||||
case DSM_BIND_START:
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
|
||||
usleep(500000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
|
||||
usleep(72000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
|
||||
usleep(50000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
|
||||
|
||||
/* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
|
||||
if (arg == DSM2_BIND_PULSES ||
|
||||
arg == DSMX_BIND_PULSES ||
|
||||
arg == DSMX8_BIND_PULSES) {
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
|
||||
usleep(500000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
|
||||
usleep(72000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
|
||||
usleep(50000);
|
||||
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
|
||||
|
||||
ret = OK;
|
||||
} else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
break;
|
||||
|
||||
case DSM_BIND_POWER_UP:
|
||||
|
@ -2615,7 +2622,7 @@ bind(int argc, char *argv[])
|
|||
#endif
|
||||
|
||||
if (argc < 3)
|
||||
errx(0, "needs argument, use dsm2 or dsmx");
|
||||
errx(0, "needs argument, use dsm2, dsmx or dsmx8");
|
||||
|
||||
if (!strcmp(argv[2], "dsm2"))
|
||||
pulses = DSM2_BIND_PULSES;
|
||||
|
@ -2624,7 +2631,7 @@ bind(int argc, char *argv[])
|
|||
else if (!strcmp(argv[2], "dsmx8"))
|
||||
pulses = DSMX8_BIND_PULSES;
|
||||
else
|
||||
errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
|
||||
errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]);
|
||||
// Test for custom pulse parameter
|
||||
if (argc > 3)
|
||||
pulses = atoi(argv[3]);
|
||||
|
|
|
@ -430,7 +430,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
|||
arming_res = TRANSITION_NOT_CHANGED;
|
||||
|
||||
if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
|
||||
if ((safety->safety_switch_available && !safety->safety_off) && status->hil_state == HIL_STATE_OFF) {
|
||||
if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) {
|
||||
print_reject_arm("NOT ARMING: Press safety switch first.");
|
||||
arming_res = TRANSITION_DENIED;
|
||||
|
||||
|
@ -516,7 +516,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
|||
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
|
||||
|
||||
if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
|
||||
if (safety->safety_switch_available && !safety->safety_off) {
|
||||
if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) {
|
||||
print_reject_arm("NOT ARMING: Press safety switch first.");
|
||||
arming_res = TRANSITION_DENIED;
|
||||
|
||||
|
@ -1156,7 +1156,7 @@ int commander_thread_main(int argc, char *argv[])
|
|||
if (status.arming_state == ARMING_STATE_STANDBY &&
|
||||
sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
|
||||
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
||||
if (safety.safety_switch_available && !safety.safety_off) {
|
||||
if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) {
|
||||
print_reject_arm("NOT ARMING: Press safety switch first.");
|
||||
|
||||
} else if (status.main_state != MAIN_STATE_MANUAL) {
|
||||
|
|
|
@ -53,11 +53,9 @@
|
|||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
@ -71,7 +69,6 @@
|
|||
#include <uORB/topics/parameter_update.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
|
@ -84,9 +81,9 @@
|
|||
*/
|
||||
extern "C" __EXPORT int mc_att_control_main(int argc, char *argv[]);
|
||||
|
||||
#define MIN_TAKEOFF_THROTTLE 0.3f
|
||||
#define YAW_DEADZONE 0.05f
|
||||
#define RATES_I_LIMIT 0.5f
|
||||
#define MIN_TAKEOFF_THRUST 0.2f
|
||||
#define RATES_I_LIMIT 0.3f
|
||||
|
||||
class MulticopterAttitudeControl
|
||||
{
|
||||
|
@ -135,15 +132,13 @@ private:
|
|||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
math::Matrix<3, 3> _R_sp; /**< attitude setpoint rotation matrix */
|
||||
math::Matrix<3, 3> _R; /**< rotation matrix for current state */
|
||||
math::Vector<3> _rates_prev; /**< angular rates on previous step */
|
||||
math::Vector<3> _rates_sp; /**< angular rates setpoint */
|
||||
math::Vector<3> _rates_int; /**< angular rates integral error */
|
||||
float _thrust_sp; /**< thrust setpoint */
|
||||
math::Vector<3> _att_control; /**< attitude control vector */
|
||||
|
||||
math::Matrix<3, 3> I; /**< identity matrix */
|
||||
math::Matrix<3, 3> _I; /**< identity matrix */
|
||||
|
||||
bool _reset_yaw_sp; /**< reset yaw setpoint flag */
|
||||
|
||||
|
@ -262,7 +257,7 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
|
|||
_actuators_0_pub(-1),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control"))
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "mc_att_control"))
|
||||
|
||||
{
|
||||
memset(&_v_att, 0, sizeof(_v_att));
|
||||
|
@ -276,15 +271,13 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
|
|||
_params.rate_i.zero();
|
||||
_params.rate_d.zero();
|
||||
|
||||
_R_sp.identity();
|
||||
_R.identity();
|
||||
_rates_prev.zero();
|
||||
_rates_sp.zero();
|
||||
_rates_int.zero();
|
||||
_thrust_sp = 0.0f;
|
||||
_att_control.zero();
|
||||
|
||||
I.identity();
|
||||
_I.identity();
|
||||
|
||||
_params_handles.roll_p = param_find("MC_ROLL_P");
|
||||
_params_handles.roll_rate_p = param_find("MC_ROLLRATE_P");
|
||||
|
@ -535,16 +528,18 @@ MulticopterAttitudeControl::control_attitude(float dt)
|
|||
_thrust_sp = _v_att_sp.thrust;
|
||||
|
||||
/* construct attitude setpoint rotation matrix */
|
||||
math::Matrix<3, 3> R_sp;
|
||||
|
||||
if (_v_att_sp.R_valid) {
|
||||
/* rotation matrix in _att_sp is valid, use it */
|
||||
_R_sp.set(&_v_att_sp.R_body[0][0]);
|
||||
R_sp.set(&_v_att_sp.R_body[0][0]);
|
||||
|
||||
} else {
|
||||
/* rotation matrix in _att_sp is not valid, use euler angles instead */
|
||||
_R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body);
|
||||
R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body);
|
||||
|
||||
/* copy rotation matrix back to setpoint struct */
|
||||
memcpy(&_v_att_sp.R_body[0][0], &_R_sp.data[0][0], sizeof(_v_att_sp.R_body));
|
||||
memcpy(&_v_att_sp.R_body[0][0], &R_sp.data[0][0], sizeof(_v_att_sp.R_body));
|
||||
_v_att_sp.R_valid = true;
|
||||
}
|
||||
|
||||
|
@ -561,23 +556,24 @@ MulticopterAttitudeControl::control_attitude(float dt)
|
|||
}
|
||||
|
||||
/* rotation matrix for current state */
|
||||
_R.set(_v_att.R);
|
||||
math::Matrix<3, 3> R;
|
||||
R.set(_v_att.R);
|
||||
|
||||
/* all input data is ready, run controller itself */
|
||||
|
||||
/* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */
|
||||
math::Vector<3> R_z(_R(0, 2), _R(1, 2), _R(2, 2));
|
||||
math::Vector<3> R_sp_z(_R_sp(0, 2), _R_sp(1, 2), _R_sp(2, 2));
|
||||
math::Vector<3> R_z(R(0, 2), R(1, 2), R(2, 2));
|
||||
math::Vector<3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2));
|
||||
|
||||
/* axis and sin(angle) of desired rotation */
|
||||
math::Vector<3> e_R = _R.transposed() * (R_z % R_sp_z);
|
||||
math::Vector<3> e_R = R.transposed() * (R_z % R_sp_z);
|
||||
|
||||
/* calculate angle error */
|
||||
float e_R_z_sin = e_R.length();
|
||||
float e_R_z_cos = R_z * R_sp_z;
|
||||
|
||||
/* calculate weight for yaw control */
|
||||
float yaw_w = _R_sp(2, 2) * _R_sp(2, 2);
|
||||
float yaw_w = R_sp(2, 2) * R_sp(2, 2);
|
||||
|
||||
/* calculate rotation matrix after roll/pitch only rotation */
|
||||
math::Matrix<3, 3> R_rp;
|
||||
|
@ -600,15 +596,15 @@ MulticopterAttitudeControl::control_attitude(float dt)
|
|||
e_R_cp(2, 1) = e_R_z_axis(0);
|
||||
|
||||
/* rotation matrix for roll/pitch only rotation */
|
||||
R_rp = _R * (I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos));
|
||||
R_rp = R * (_I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos));
|
||||
|
||||
} else {
|
||||
/* zero roll/pitch rotation */
|
||||
R_rp = _R;
|
||||
R_rp = R;
|
||||
}
|
||||
|
||||
/* R_rp and _R_sp has the same Z axis, calculate yaw error */
|
||||
math::Vector<3> R_sp_x(_R_sp(0, 0), _R_sp(1, 0), _R_sp(2, 0));
|
||||
/* R_rp and R_sp has the same Z axis, calculate yaw error */
|
||||
math::Vector<3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0));
|
||||
math::Vector<3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0));
|
||||
e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w;
|
||||
|
||||
|
@ -616,7 +612,7 @@ MulticopterAttitudeControl::control_attitude(float dt)
|
|||
/* for large thrust vector rotations use another rotation method:
|
||||
* calculate angle and axis for R -> R_sp rotation directly */
|
||||
math::Quaternion q;
|
||||
q.from_dcm(_R.transposed() * _R_sp);
|
||||
q.from_dcm(R.transposed() * R_sp);
|
||||
math::Vector<3> e_R_d = q.imag();
|
||||
e_R_d.normalize();
|
||||
e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0));
|
||||
|
@ -658,7 +654,7 @@ MulticopterAttitudeControl::control_attitude_rates(float dt)
|
|||
_rates_prev = rates;
|
||||
|
||||
/* update integral only if not saturated on low limit */
|
||||
if (_thrust_sp > 0.1f) {
|
||||
if (_thrust_sp > MIN_TAKEOFF_THRUST) {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (fabsf(_att_control(i)) < _thrust_sp) {
|
||||
float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt;
|
||||
|
@ -695,9 +691,6 @@ MulticopterAttitudeControl::task_main()
|
|||
_manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||
|
||||
/* rate limit attitude updates to 200Hz, failsafe against spam, normally runs at the same rate as attitude estimator */
|
||||
orb_set_interval(_v_att_sub, 5);
|
||||
|
||||
/* initialize parameters cache */
|
||||
parameters_update();
|
||||
|
||||
|
@ -767,10 +760,12 @@ MulticopterAttitudeControl::task_main()
|
|||
}
|
||||
|
||||
} else {
|
||||
/* attitude controller disabled */
|
||||
// TODO poll 'attitude_rates_setpoint' topic
|
||||
_rates_sp.zero();
|
||||
_thrust_sp = 0.0f;
|
||||
/* attitude controller disabled, poll rates setpoint topic */
|
||||
vehicle_rates_setpoint_poll();
|
||||
_rates_sp(0) = _v_rates_sp.roll;
|
||||
_rates_sp(1) = _v_rates_sp.pitch;
|
||||
_rates_sp(2) = _v_rates_sp.yaw;
|
||||
_thrust_sp = _v_rates_sp.thrust;
|
||||
}
|
||||
|
||||
if (_v_control_mode.flag_control_rates_enabled) {
|
||||
|
|
|
@ -41,16 +41,135 @@
|
|||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/**
|
||||
* Roll P gain
|
||||
*
|
||||
* Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f);
|
||||
|
||||
/**
|
||||
* Roll rate P gain
|
||||
*
|
||||
* Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f);
|
||||
|
||||
/**
|
||||
* Roll rate I gain
|
||||
*
|
||||
* Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f);
|
||||
|
||||
/**
|
||||
* Roll rate D gain
|
||||
*
|
||||
* Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.002f);
|
||||
|
||||
/**
|
||||
* Pitch P gain
|
||||
*
|
||||
* Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
|
||||
*
|
||||
* @unit 1/s
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f);
|
||||
|
||||
/**
|
||||
* Pitch rate P gain
|
||||
*
|
||||
* Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f);
|
||||
|
||||
/**
|
||||
* Pitch rate I gain
|
||||
*
|
||||
* Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f);
|
||||
|
||||
/**
|
||||
* Pitch rate D gain
|
||||
*
|
||||
* Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.002f);
|
||||
|
||||
/**
|
||||
* Yaw P gain
|
||||
*
|
||||
* Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
|
||||
*
|
||||
* @unit 1/s
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f);
|
||||
|
||||
/**
|
||||
* Yaw rate P gain
|
||||
*
|
||||
* Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f);
|
||||
|
||||
/**
|
||||
* Yaw rate I gain
|
||||
*
|
||||
* Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f);
|
||||
|
||||
/**
|
||||
* Yaw rate D gain
|
||||
*
|
||||
* Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
|
||||
|
||||
/**
|
||||
* Yaw feed forward
|
||||
*
|
||||
* Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f);
|
||||
|
|
|
@ -51,7 +51,6 @@
|
|||
#include <errno.h>
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <time.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
@ -68,7 +67,6 @@
|
|||
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
|
||||
#include <systemlib/param/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/pid/pid.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <lib/geo/geo.h>
|
||||
|
@ -732,7 +730,6 @@ MulticopterPositionControl::task_main()
|
|||
} else {
|
||||
/* run position & altitude controllers, calculate velocity setpoint */
|
||||
math::Vector<3> pos_err;
|
||||
float err_x, err_y;
|
||||
get_vector_to_next_waypoint_fast(_global_pos.lat, _global_pos.lon, _lat_sp, _lon_sp, &pos_err.data[0], &pos_err.data[1]);
|
||||
pos_err(2) = -(_alt_sp - alt);
|
||||
|
||||
|
|
|
@ -39,20 +39,164 @@
|
|||
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.0f);
|
||||
/**
|
||||
* Minimum thrust
|
||||
*
|
||||
* Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.1f);
|
||||
|
||||
/**
|
||||
* Maximum thrust
|
||||
*
|
||||
* Limit max allowed thrust.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.0f);
|
||||
|
||||
/**
|
||||
* Proportional gain for vertical position error
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f);
|
||||
|
||||
/**
|
||||
* Proportional gain for vertical velocity error
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_P, 0.1f);
|
||||
|
||||
/**
|
||||
* Integral gain for vertical velocity error
|
||||
*
|
||||
* Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_I, 0.02f);
|
||||
|
||||
/**
|
||||
* Differential gain for vertical velocity error
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
|
||||
|
||||
/**
|
||||
* Maximum vertical velocity
|
||||
*
|
||||
* Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY).
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Vertical velocity feed forward
|
||||
*
|
||||
* Feed forward weight for altitude control in stabilized modes (SEATBELT, EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_FF, 0.5f);
|
||||
|
||||
/**
|
||||
* Proportional gain for horizontal position error
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_P, 1.0f);
|
||||
|
||||
/**
|
||||
* Proportional gain for horizontal velocity error
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_P, 0.1f);
|
||||
|
||||
/**
|
||||
* Integral gain for horizontal velocity error
|
||||
*
|
||||
* Non-zero value allows to resist wind.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_I, 0.02f);
|
||||
|
||||
/**
|
||||
* Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
|
||||
|
||||
/**
|
||||
* Maximum horizontal velocity
|
||||
*
|
||||
* Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY).
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Horizontal velocity feed forward
|
||||
*
|
||||
* Feed forward weight for position control in position control mode (EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
|
||||
|
||||
/**
|
||||
* Maximum tilt
|
||||
*
|
||||
* Limits maximum tilt in AUTO and EASY modes.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.57
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 1.0f);
|
||||
|
||||
/**
|
||||
* Landing descend rate
|
||||
*
|
||||
* @min 0.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 1.0f);
|
||||
|
||||
/**
|
||||
* Maximum landing tilt
|
||||
*
|
||||
* Limits maximum tilt on landing.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.57
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_LAND_TILT, 0.3f);
|
||||
|
|
|
@ -305,6 +305,12 @@ private:
|
|||
void start_land();
|
||||
void start_land_home();
|
||||
|
||||
/**
|
||||
* Fork for state transitions
|
||||
*/
|
||||
void request_loiter_or_ready();
|
||||
void request_mission_if_available();
|
||||
|
||||
/**
|
||||
* Guards offboard mission
|
||||
*/
|
||||
|
@ -699,24 +705,17 @@ Navigator::task_main()
|
|||
} else {
|
||||
/* MISSION switch */
|
||||
if (_vstatus.mission_switch == MISSION_SWITCH_LOITER) {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
request_loiter_or_ready();
|
||||
stick_mode = true;
|
||||
|
||||
} else if (_vstatus.mission_switch == MISSION_SWITCH_MISSION) {
|
||||
/* switch to mission only if available */
|
||||
if (_mission.current_mission_available()) {
|
||||
dispatch(EVENT_MISSION_REQUESTED);
|
||||
|
||||
} else {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
|
||||
request_mission_if_available();
|
||||
stick_mode = true;
|
||||
}
|
||||
|
||||
if (!stick_mode && _vstatus.return_switch == RETURN_SWITCH_NORMAL && myState == NAV_STATE_RTL) {
|
||||
/* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
request_mission_if_available();
|
||||
stick_mode = true;
|
||||
}
|
||||
}
|
||||
|
@ -733,17 +732,11 @@ Navigator::task_main()
|
|||
break;
|
||||
|
||||
case NAV_STATE_LOITER:
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
request_loiter_or_ready();
|
||||
break;
|
||||
|
||||
case NAV_STATE_MISSION:
|
||||
if (_mission.current_mission_available()) {
|
||||
dispatch(EVENT_MISSION_REQUESTED);
|
||||
|
||||
} else {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
|
||||
request_mission_if_available();
|
||||
break;
|
||||
|
||||
case NAV_STATE_RTL:
|
||||
|
@ -770,12 +763,7 @@ Navigator::task_main()
|
|||
} else {
|
||||
/* on first switch to AUTO try mission by default, if none is available fallback to loiter */
|
||||
if (myState == NAV_STATE_NONE) {
|
||||
if (_mission.current_mission_available()) {
|
||||
dispatch(EVENT_MISSION_REQUESTED);
|
||||
|
||||
} else {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
request_mission_if_available();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1071,7 +1059,7 @@ Navigator::start_loiter()
|
|||
float min_alt_amsl = _parameters.min_altitude + _home_pos.alt;
|
||||
|
||||
/* use current altitude if above min altitude set by parameter */
|
||||
if (_global_pos.alt < min_alt_amsl) {
|
||||
if (_global_pos.alt < min_alt_amsl && !_vstatus.is_rotary_wing) {
|
||||
_pos_sp_triplet.current.alt = min_alt_amsl;
|
||||
mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
|
||||
|
||||
|
@ -1397,6 +1385,28 @@ Navigator::set_rtl_item()
|
|||
_pos_sp_triplet_updated = true;
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::request_loiter_or_ready()
|
||||
{
|
||||
if (_vstatus.condition_landed) {
|
||||
dispatch(EVENT_READY_REQUESTED);
|
||||
|
||||
} else {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::request_mission_if_available()
|
||||
{
|
||||
if (_mission.current_mission_available()) {
|
||||
dispatch(EVENT_MISSION_REQUESTED);
|
||||
|
||||
} else {
|
||||
request_loiter_or_ready();
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item)
|
||||
{
|
||||
|
@ -1555,13 +1565,7 @@ Navigator::on_mission_item_reached()
|
|||
/* loiter at last waypoint */
|
||||
_reset_loiter_pos = false;
|
||||
mavlink_log_info(_mavlink_fd, "[navigator] mission completed");
|
||||
|
||||
if (_vstatus.condition_landed) {
|
||||
dispatch(EVENT_READY_REQUESTED);
|
||||
|
||||
} else {
|
||||
dispatch(EVENT_LOITER_REQUESTED);
|
||||
}
|
||||
request_loiter_or_ready();
|
||||
}
|
||||
|
||||
} else if (myState == NAV_STATE_RTL) {
|
||||
|
|
|
@ -53,68 +53,87 @@
|
|||
*/
|
||||
|
||||
/**
|
||||
* Minimum altitude
|
||||
* Minimum altitude (fixed wing only)
|
||||
*
|
||||
* Minimum altitude above home for LOITER.
|
||||
*
|
||||
* @unit meters
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
|
||||
|
||||
/**
|
||||
* Waypoint acceptance radius.
|
||||
* Waypoint acceptance radius
|
||||
*
|
||||
* Default value of acceptance radius (if not specified in mission item).
|
||||
*
|
||||
* @unit meters
|
||||
* @min 0.0
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
|
||||
|
||||
/**
|
||||
* Loiter radius.
|
||||
* Loiter radius (fixed wing only)
|
||||
*
|
||||
* Default value of loiter radius (if not specified in mission item).
|
||||
*
|
||||
* @unit meters
|
||||
* @min 0.0
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
|
||||
|
||||
/**
|
||||
* Enable onboard mission
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
|
||||
|
||||
/**
|
||||
* Default take-off altitude.
|
||||
* Take-off altitude
|
||||
*
|
||||
* Even if first waypoint has altitude less then NAV_TAKEOFF_ALT above home position, system will climb to NAV_TAKEOFF_ALT on takeoff, then go to waypoint.
|
||||
*
|
||||
* @unit meters
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
|
||||
PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f);
|
||||
|
||||
/**
|
||||
* Landing altitude.
|
||||
* Landing altitude
|
||||
*
|
||||
* Slowly descend from this altitude when landing.
|
||||
* Stay at this altitude above home position after RTL descending. Land (i.e. slowly descend) from this altitude if autolanding allowed.
|
||||
*
|
||||
* @unit meters
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
|
||||
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f);
|
||||
|
||||
/**
|
||||
* Return-to-land altitude.
|
||||
* Return-To-Launch altitude
|
||||
*
|
||||
* Minimum altitude for going home in RTL mode.
|
||||
* Minimum altitude above home position for going home in RTL mode.
|
||||
*
|
||||
* @unit meters
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f);
|
||||
|
||||
/**
|
||||
* Return-to-land delay.
|
||||
* Return-To-Launch delay
|
||||
*
|
||||
* Delay after descend before landing.
|
||||
* Delay after descend before landing in RTL mode.
|
||||
* If set to -1 the system will not land but loiter at NAV_LAND_ALT.
|
||||
*
|
||||
* @unit seconds
|
||||
* @group Navigation
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f);
|
||||
|
||||
/**
|
||||
* Enable parachute deployment.
|
||||
* Enable parachute deployment
|
||||
*
|
||||
* @group Navigation
|
||||
*/
|
||||
|
|
|
@ -42,14 +42,11 @@
|
|||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <float.h>
|
||||
#include <string.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <termios.h>
|
||||
#include <errno.h>
|
||||
#include <limits.h>
|
||||
#include <math.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -162,6 +162,7 @@ dsm_guess_format(bool reset)
|
|||
0xff, /* 8 channels (DX8) */
|
||||
0x1ff, /* 9 channels (DX9, etc.) */
|
||||
0x3ff, /* 10 channels (DX10) */
|
||||
0x1fff, /* 13 channels (DX10t) */
|
||||
0x3fff /* 18 channels (DX10) */
|
||||
};
|
||||
unsigned votes10 = 0;
|
||||
|
@ -368,11 +369,25 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
|
|||
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 (dsm_channel_shift == 11)
|
||||
value /= 2;
|
||||
/* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
|
||||
if (dsm_channel_shift == 10)
|
||||
value *= 2;
|
||||
|
||||
value += 998;
|
||||
/*
|
||||
* Spektrum scaling is special. There are these basic considerations
|
||||
*
|
||||
* * Midpoint is 1520 us
|
||||
* * 100% travel channels are +- 400 us
|
||||
*
|
||||
* We obey the original Spektrum scaling (so a default setup will scale from
|
||||
* 1100 - 1900 us), but we do not obey the weird 1520 us center point
|
||||
* and instead (correctly) center the center around 1500 us. This is in order
|
||||
* to get something useful without requiring the user to calibrate on a digital
|
||||
* link for no reason.
|
||||
*/
|
||||
|
||||
/* scaled integer for decent accuracy while staying efficient */
|
||||
value = ((((int)value - 1024) * 1000) / 1700) + 1500;
|
||||
|
||||
/*
|
||||
* Store the decoded channel into the R/C input buffer, taking into
|
||||
|
@ -400,6 +415,15 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
|
|||
values[channel] = value;
|
||||
}
|
||||
|
||||
/*
|
||||
* Spektrum likes to send junk in higher channel numbers to fill
|
||||
* their packets. We don't know about a 13 channel model in their TX
|
||||
* lines, so if we get a channel count of 13, we'll return 12 (the last
|
||||
* data index that is stable).
|
||||
*/
|
||||
if (*num_values == 13)
|
||||
*num_values = 12;
|
||||
|
||||
if (dsm_channel_shift == 11) {
|
||||
/* Set the 11-bit data indicator */
|
||||
*num_values |= 0x8000;
|
||||
|
|
|
@ -179,7 +179,7 @@ mixer_tick(void)
|
|||
((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
|
||||
/* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
|
||||
/* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
|
||||
/* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
|
||||
/* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))
|
||||
)
|
||||
);
|
||||
|
||||
|
|
|
@ -566,7 +566,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
|||
break;
|
||||
|
||||
case PX4IO_P_SETUP_DSM:
|
||||
dsm_bind(value & 0x0f, (value >> 4) & 7);
|
||||
dsm_bind(value & 0x0f, (value >> 4) & 0xF);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
|
Loading…
Reference in New Issue