sensors split rc_update into new standalone module

This commit is contained in:
Daniel Agar 2019-11-24 13:25:11 -05:00 committed by GitHub
parent 28755d5bbf
commit bc182e94e6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
80 changed files with 874 additions and 531 deletions

View File

@ -234,6 +234,7 @@ replay tryapplyparams
simulator start -c $simulator_tcp_port
tone_alarm start
gpssim start
rc_update start
sensors start
commander start
navigator start

View File

@ -310,6 +310,12 @@ else
tune_control play -t 2
fi
#
# RC update (map raw RC input to calibrate manual control)
# start before commander
#
rc_update start
#
# Sensors System (start before Commander so Preflight checks are properly run).
# Commander needs to be this early for in-air-restarts.

View File

@ -50,6 +50,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -72,6 +72,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -83,6 +83,7 @@ px4_add_board(
mc_rate_control
mc_pos_control
navigator
rc_update
sensors
#sih
simulator

View File

@ -76,6 +76,7 @@ px4_add_board(
mc_att_control
mc_rate_control
mc_pos_control
rc_update
sensors
#sih
vmount

View File

@ -83,6 +83,7 @@ px4_add_board(
mc_rate_control
mc_pos_control
navigator
rc_update
sensors
sih
simulator

View File

@ -75,6 +75,7 @@ px4_add_board(
mc_att_control
mc_rate_control
mc_pos_control
rc_update
sensors
sih
vmount

View File

@ -72,6 +72,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -72,6 +72,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -47,6 +47,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -45,6 +45,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -30,6 +30,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
sensors
SYSTEMCMDS
bl_update

View File

@ -51,6 +51,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -49,6 +49,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -77,6 +77,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -44,6 +44,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
sensors
SYSTEMCMDS
bl_update

View File

@ -52,6 +52,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
#rover_pos_control
sensors
#sih

View File

@ -52,6 +52,7 @@ px4_add_board(
mc_rate_control
micrortps_bridge
navigator
rc_update
#rover_pos_control
sensors
#sih

View File

@ -70,6 +70,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -76,6 +76,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -73,6 +73,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -60,6 +60,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
#rover_pos_control
sensors
#sih

View File

@ -39,6 +39,7 @@ px4_add_board(
mc_rate_control
mc_pos_control
navigator
rc_update
sensors
sih
#vtol_att_control

View File

@ -48,7 +48,7 @@ px4_add_board(
magnetometer/hmc5883
#mkblctrl
#optical_flow # all available optical flow drivers
optical_flow/px4flow
#optical_flow/px4flow
#osd
#pca9685
#protocol_splitter
@ -83,6 +83,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
#rover_pos_control
sensors
#sih

View File

@ -54,6 +54,7 @@ px4_add_board(
logger
mavlink
navigator
rc_update
sensors
vmount
SYSTEMCMDS

View File

@ -79,6 +79,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
vmount
#vtol_att_control

View File

@ -52,6 +52,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
sensors
vmount
SYSTEMCMDS

View File

@ -48,6 +48,7 @@ px4_add_board(
mavlink
navigator
battery_status
rc_update
sensors
vmount

View File

@ -82,6 +82,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
#rover_pos_control
sensors
#sih

View File

@ -82,6 +82,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -82,6 +82,7 @@ px4_add_board(
mc_rate_control
micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -78,6 +78,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
sih
vmount

View File

@ -73,6 +73,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -73,6 +73,7 @@ px4_add_board(
mc_rate_control
micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -73,6 +73,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -75,6 +75,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -74,6 +74,7 @@ px4_add_board(
mc_rate_control
micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -78,6 +78,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
sih
vmount

View File

@ -78,6 +78,7 @@ px4_add_board(
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -57,6 +57,7 @@ px4_add_board(
logger
mavlink
navigator
rc_update
sensors
vmount
SYSTEMCMDS

View File

@ -78,6 +78,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
sih
vmount

View File

@ -66,6 +66,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
sensors
sih
vmount

View File

@ -56,6 +56,7 @@ px4_add_board(
logger
mavlink
navigator
rc_update
rover_pos_control
sensors
vmount

View File

@ -78,6 +78,7 @@ px4_add_board(
mc_rate_control
micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -77,6 +77,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -77,6 +77,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
rover_pos_control
sensors
sih

View File

@ -45,6 +45,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
sih
vmount

View File

@ -43,6 +43,7 @@ px4_add_board(
mc_pos_control
navigator
battery_status
rc_update
sensors
sih
#simulator

View File

@ -38,6 +38,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
replay
rover_pos_control
sensors

View File

@ -41,6 +41,7 @@ px4_add_board(
micrortps_bridge
navigator
replay
rc_update
rover_pos_control
sensors
#sih

View File

@ -41,6 +41,7 @@ px4_add_board(
mc_pos_control
navigator
replay
rc_update
sensors
simulator
vmount

View File

@ -54,6 +54,7 @@ px4_add_board(
mc_pos_control
mc_rate_control
navigator
rc_update
sensors
sih
vmount

View File

@ -49,6 +49,7 @@ const char *get_commands()
"param set CAL_MAG0_ID 196608\n"
// "rgbled start\n"
// "tone_alarm start\n"
"rc_update start\n"
"commander start --hil\n"
"sensors start\n"
"ekf2 start\n"

View File

@ -19,6 +19,7 @@ tone_alarm start
gpssim start
pwm_out_sim start
rc_update start
sensors start
commander start
land_detector start vtol
@ -50,6 +51,7 @@ logger status
pwm_out_sim status
sensors status
commander status
rc_update stop
land_detector status
navigator status
ekf2 status

View File

@ -62,6 +62,7 @@ gps start -d /dev/ttyS2 -s -p ubx
bbblue_adc start
bbblue_adc test
rc_update start
sensors start
commander start
navigator start

View File

@ -62,6 +62,7 @@ gps start -d /dev/ttyS2 -s -p ubx
bbblue_adc start
bbblue_adc test
rc_update start
sensors start
commander start
navigator start

View File

@ -43,6 +43,7 @@ df_ak8963_wrapper start -R 32
#df_bebop_rangefinder_wrapper start
gps start -d /dev/ttyPA1
bebop_flow start
rc_update start
sensors start
commander start
ekf2 start

View File

@ -27,6 +27,7 @@ sleep 1
df_mpu9250_wrapper start
df_bmp280_wrapper start
gps start -d /dev/tty-4
rc_update start
sensors start
commander start
ekf2 start

View File

@ -27,6 +27,7 @@ sleep 1
df_mpu9250_wrapper start
df_bmp280_wrapper start
gps start -d /dev/tty-4
rc_update start
sensors start
commander start
ekf2 start

View File

@ -12,6 +12,7 @@ df_trone_wrapper start
#df_ltc2946_wrapper start # (currently not working on all boards...)
#df_isl29501_wrapper start
sleep 1
rc_update start
sensors start
commander start
ekf2 start

View File

@ -38,6 +38,7 @@ param set ATT_W_ACC 0.0002
param set ATT_W_MAG 0.002
param set ATT_W_GYRO_BIAS 0.05
sleep 1
rc_update start
commander start -hil
sensors start
ekf2 start

View File

@ -176,6 +176,7 @@ fi
qshell df_mpu9250_wrapper start
qshell df_bmp280_wrapper start
qshell rc_update start
qshell sensors start
if param compare SYS_MC_EST_GROUP 1

View File

@ -77,6 +77,7 @@ param set UART_ESC_MOTOR4 3
sleep 1
df_mpu9250_wrapper start
df_bmp280_wrapper start
rc_update start
sensors start
commander start
ekf2 start

View File

@ -21,6 +21,7 @@ df_ms5611_wrapper start
rgbled start -b 1
ocpoc_adc start
gps start -d /dev/ttyS3 -s
rc_update start
sensors start
commander start
navigator start

View File

@ -24,6 +24,7 @@ df_ms5611_wrapper start
navio_rgbled start
navio_adc start
gps start -d /dev/spidev0.0 -i spi -p ubx
rc_update start
sensors start
commander start
navigator start

View File

@ -24,6 +24,7 @@ navio_rgbled start
navio_adc start
gps start -d /dev/spidev0.0 -i spi -p ubx
ms4525_airspeed start
rc_update start
sensors start
commander start
navigator start

View File

@ -13,6 +13,7 @@ param set SYS_AUTOSTART 1001
param set MAV_BROADCAST 1
param set MAV_TYPE 2
dataman start
rc_update start
sensors start -hil
commander start -hil
navigator start

View File

@ -17,6 +17,7 @@ param set MAV_TYPE 2
df_mpu9250_wrapper start -R 10
df_ms5611_wrapper start
gps start -d /dev/ttyACM0 -i uart -p ubx
rc_update start
sensors start
commander start
ekf2 start

View File

@ -24,6 +24,7 @@ df_ms5611_wrapper start
navio_rgbled start
navio_adc start
gps start -d /dev/spidev0.0 -i spi -p ubx
rc_update start
sensors start
commander start
navigator start

View File

@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2015-2019 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
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE modules__rc_update
MAIN rc_update
SRCS
rc_update.cpp
parameters.cpp
DEPENDS
mathlib
)

View File

@ -0,0 +1,325 @@
/****************************************************************************
*
* Copyright (c) 2016 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file parameters.cpp
*
* @author Beat Kueng <beat-kueng@gmx.net>
*/
#include "parameters.h"
namespace RCUpdate
{
void initialize_parameter_handles(ParameterHandles &parameter_handles)
{
/* basic r/c parameters */
for (unsigned i = 0; i < RC_MAX_CHAN_COUNT; i++) {
char nbuf[16];
/* min values */
sprintf(nbuf, "RC%d_MIN", i + 1);
parameter_handles.min[i] = param_find(nbuf);
/* trim values */
sprintf(nbuf, "RC%d_TRIM", i + 1);
parameter_handles.trim[i] = param_find(nbuf);
/* max values */
sprintf(nbuf, "RC%d_MAX", i + 1);
parameter_handles.max[i] = param_find(nbuf);
/* channel reverse */
sprintf(nbuf, "RC%d_REV", i + 1);
parameter_handles.rev[i] = param_find(nbuf);
/* channel deadzone */
sprintf(nbuf, "RC%d_DZ", i + 1);
parameter_handles.dz[i] = param_find(nbuf);
}
/* mandatory input switched, mapped to channels 1-4 per default */
parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL");
parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW");
parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
parameter_handles.rc_map_return_sw = param_find("RC_MAP_RETURN_SW");
parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
parameter_handles.rc_map_rattitude_sw = param_find("RC_MAP_RATT_SW");
parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
parameter_handles.rc_map_kill_sw = param_find("RC_MAP_KILL_SW");
parameter_handles.rc_map_arm_sw = param_find("RC_MAP_ARM_SW");
parameter_handles.rc_map_trans_sw = param_find("RC_MAP_TRANS_SW");
parameter_handles.rc_map_gear_sw = param_find("RC_MAP_GEAR_SW");
parameter_handles.rc_map_stab_sw = param_find("RC_MAP_STAB_SW");
parameter_handles.rc_map_man_sw = param_find("RC_MAP_MAN_SW");
parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
parameter_handles.rc_map_aux3 = param_find("RC_MAP_AUX3");
parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
parameter_handles.rc_map_aux6 = param_find("RC_MAP_AUX6");
/* RC to parameter mapping for changing parameters with RC */
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
char name[rc_parameter_map_s::PARAM_ID_LEN];
snprintf(name, rc_parameter_map_s::PARAM_ID_LEN, "RC_MAP_PARAM%d",
i + 1); // shifted by 1 because param name starts at 1
parameter_handles.rc_map_param[i] = param_find(name);
}
parameter_handles.rc_map_flightmode = param_find("RC_MAP_FLTMODE");
/* RC thresholds */
parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
parameter_handles.rc_rattitude_th = param_find("RC_RATT_TH");
parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
parameter_handles.rc_killswitch_th = param_find("RC_KILLSWITCH_TH");
parameter_handles.rc_armswitch_th = param_find("RC_ARMSWITCH_TH");
parameter_handles.rc_trans_th = param_find("RC_TRANS_TH");
parameter_handles.rc_gear_th = param_find("RC_GEAR_TH");
parameter_handles.rc_stab_th = param_find("RC_STAB_TH");
parameter_handles.rc_man_th = param_find("RC_MAN_TH");
/* RC low pass filter configuration */
parameter_handles.rc_flt_smp_rate = param_find("RC_FLT_SMP_RATE");
parameter_handles.rc_flt_cutoff = param_find("RC_FLT_CUTOFF");
// These are parameters for which QGroundControl always expects to be returned in a list request.
// We do a param_find here to force them into the list.
(void)param_find("RC_CHAN_CNT");
}
int update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters)
{
bool rc_valid = true;
float tmpScaleFactor = 0.0f;
float tmpRevFactor = 0.0f;
int ret = PX4_OK;
/* rc values */
for (unsigned int i = 0; i < RC_MAX_CHAN_COUNT; i++) {
param_get(parameter_handles.min[i], &(parameters.min[i]));
param_get(parameter_handles.trim[i], &(parameters.trim[i]));
param_get(parameter_handles.max[i], &(parameters.max[i]));
param_get(parameter_handles.rev[i], &(parameters.rev[i]));
param_get(parameter_handles.dz[i], &(parameters.dz[i]));
tmpScaleFactor = (1.0f / ((parameters.max[i] - parameters.min[i]) / 2.0f) * parameters.rev[i]);
tmpRevFactor = tmpScaleFactor * parameters.rev[i];
/* handle blowup in the scaling factor calculation */
if (!PX4_ISFINITE(tmpScaleFactor) ||
(tmpRevFactor < 0.000001f) ||
(tmpRevFactor > 0.2f)) {
PX4_WARN("RC chan %u not sane, scaling: %8.6f, rev: %d", i, (double)tmpScaleFactor, (int)(parameters.rev[i]));
/* scaling factors do not make sense, lock them down */
parameters.scaling_factor[i] = 0.0f;
rc_valid = false;
} else {
parameters.scaling_factor[i] = tmpScaleFactor;
}
}
/* handle wrong values */
if (!rc_valid) {
PX4_ERR("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
}
const char *paramerr = "FAIL PARM LOAD";
/* channel mapping */
if (param_get(parameter_handles.rc_map_roll, &(parameters.rc_map_roll)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_pitch, &(parameters.rc_map_pitch)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_yaw, &(parameters.rc_map_yaw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_throttle, &(parameters.rc_map_throttle)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_failsafe, &(parameters.rc_map_failsafe)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_mode_sw, &(parameters.rc_map_mode_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_return_sw, &(parameters.rc_map_return_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_rattitude_sw, &(parameters.rc_map_rattitude_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_posctl_sw, &(parameters.rc_map_posctl_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_loiter_sw, &(parameters.rc_map_loiter_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_acro_sw, &(parameters.rc_map_acro_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_offboard_sw, &(parameters.rc_map_offboard_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_kill_sw, &(parameters.rc_map_kill_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_arm_sw, &(parameters.rc_map_arm_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_trans_sw, &(parameters.rc_map_trans_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_flaps, &(parameters.rc_map_flaps)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_gear_sw, &(parameters.rc_map_gear_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_stab_sw, &(parameters.rc_map_stab_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_man_sw, &(parameters.rc_map_man_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
param_get(parameter_handles.rc_map_aux1, &(parameters.rc_map_aux1));
param_get(parameter_handles.rc_map_aux2, &(parameters.rc_map_aux2));
param_get(parameter_handles.rc_map_aux3, &(parameters.rc_map_aux3));
param_get(parameter_handles.rc_map_aux4, &(parameters.rc_map_aux4));
param_get(parameter_handles.rc_map_aux5, &(parameters.rc_map_aux5));
param_get(parameter_handles.rc_map_aux6, &(parameters.rc_map_aux6));
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
param_get(parameter_handles.rc_map_param[i], &(parameters.rc_map_param[i]));
}
param_get(parameter_handles.rc_map_flightmode, &(parameters.rc_map_flightmode));
param_get(parameter_handles.rc_fails_thr, &(parameters.rc_fails_thr));
param_get(parameter_handles.rc_assist_th, &(parameters.rc_assist_th));
parameters.rc_assist_inv = (parameters.rc_assist_th < 0);
parameters.rc_assist_th = fabsf(parameters.rc_assist_th);
param_get(parameter_handles.rc_auto_th, &(parameters.rc_auto_th));
parameters.rc_auto_inv = (parameters.rc_auto_th < 0);
parameters.rc_auto_th = fabsf(parameters.rc_auto_th);
param_get(parameter_handles.rc_rattitude_th, &(parameters.rc_rattitude_th));
parameters.rc_rattitude_inv = (parameters.rc_rattitude_th < 0);
parameters.rc_rattitude_th = fabsf(parameters.rc_rattitude_th);
param_get(parameter_handles.rc_posctl_th, &(parameters.rc_posctl_th));
parameters.rc_posctl_inv = (parameters.rc_posctl_th < 0);
parameters.rc_posctl_th = fabsf(parameters.rc_posctl_th);
param_get(parameter_handles.rc_return_th, &(parameters.rc_return_th));
parameters.rc_return_inv = (parameters.rc_return_th < 0);
parameters.rc_return_th = fabsf(parameters.rc_return_th);
param_get(parameter_handles.rc_loiter_th, &(parameters.rc_loiter_th));
parameters.rc_loiter_inv = (parameters.rc_loiter_th < 0);
parameters.rc_loiter_th = fabsf(parameters.rc_loiter_th);
param_get(parameter_handles.rc_acro_th, &(parameters.rc_acro_th));
parameters.rc_acro_inv = (parameters.rc_acro_th < 0);
parameters.rc_acro_th = fabsf(parameters.rc_acro_th);
param_get(parameter_handles.rc_offboard_th, &(parameters.rc_offboard_th));
parameters.rc_offboard_inv = (parameters.rc_offboard_th < 0);
parameters.rc_offboard_th = fabsf(parameters.rc_offboard_th);
param_get(parameter_handles.rc_killswitch_th, &(parameters.rc_killswitch_th));
parameters.rc_killswitch_inv = (parameters.rc_killswitch_th < 0);
parameters.rc_killswitch_th = fabsf(parameters.rc_killswitch_th);
param_get(parameter_handles.rc_armswitch_th, &(parameters.rc_armswitch_th));
parameters.rc_armswitch_inv = (parameters.rc_armswitch_th < 0);
parameters.rc_armswitch_th = fabsf(parameters.rc_armswitch_th);
param_get(parameter_handles.rc_trans_th, &(parameters.rc_trans_th));
parameters.rc_trans_inv = (parameters.rc_trans_th < 0);
parameters.rc_trans_th = fabsf(parameters.rc_trans_th);
param_get(parameter_handles.rc_gear_th, &(parameters.rc_gear_th));
parameters.rc_gear_inv = (parameters.rc_gear_th < 0);
parameters.rc_gear_th = fabsf(parameters.rc_gear_th);
param_get(parameter_handles.rc_stab_th, &(parameters.rc_stab_th));
parameters.rc_stab_inv = (parameters.rc_stab_th < 0);
parameters.rc_stab_th = fabsf(parameters.rc_stab_th);
param_get(parameter_handles.rc_man_th, &(parameters.rc_man_th));
parameters.rc_man_inv = (parameters.rc_man_th < 0);
parameters.rc_man_th = fabsf(parameters.rc_man_th);
param_get(parameter_handles.rc_flt_smp_rate, &(parameters.rc_flt_smp_rate));
parameters.rc_flt_smp_rate = math::max(1.0f, parameters.rc_flt_smp_rate);
param_get(parameter_handles.rc_flt_cutoff, &(parameters.rc_flt_cutoff));
/* make sure the filter is in its stable region -> fc < fs/2 */
parameters.rc_flt_cutoff = math::min(parameters.rc_flt_cutoff, (parameters.rc_flt_smp_rate / 2) - 1.f);
return ret;
}
} /* namespace RCUpdate */

View File

@ -0,0 +1,207 @@
/****************************************************************************
*
* Copyright (c) 2016 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
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/**
* @file parameters.h
*
* defines the list of parameters that are used within the RCUpdate module
*
* @author Beat Kueng <beat-kueng@gmx.net>
*/
#include <px4_platform_common/px4_config.h>
#include <drivers/drv_rc_input.h>
#include <parameters/param.h>
#include <mathlib/mathlib.h>
#include <uORB/topics/rc_parameter_map.h>
#include <uORB/topics/input_rc.h>
namespace RCUpdate
{
static constexpr unsigned RC_MAX_CHAN_COUNT =
input_rc_s::RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
struct Parameters {
float min[RC_MAX_CHAN_COUNT];
float trim[RC_MAX_CHAN_COUNT];
float max[RC_MAX_CHAN_COUNT];
float rev[RC_MAX_CHAN_COUNT];
float dz[RC_MAX_CHAN_COUNT];
float scaling_factor[RC_MAX_CHAN_COUNT];
int32_t rc_map_roll;
int32_t rc_map_pitch;
int32_t rc_map_yaw;
int32_t rc_map_throttle;
int32_t rc_map_failsafe;
int32_t rc_map_mode_sw;
int32_t rc_map_return_sw;
int32_t rc_map_rattitude_sw;
int32_t rc_map_posctl_sw;
int32_t rc_map_loiter_sw;
int32_t rc_map_acro_sw;
int32_t rc_map_offboard_sw;
int32_t rc_map_kill_sw;
int32_t rc_map_arm_sw;
int32_t rc_map_trans_sw;
int32_t rc_map_gear_sw;
int32_t rc_map_stab_sw;
int32_t rc_map_man_sw;
int32_t rc_map_flaps;
int32_t rc_map_aux1;
int32_t rc_map_aux2;
int32_t rc_map_aux3;
int32_t rc_map_aux4;
int32_t rc_map_aux5;
int32_t rc_map_aux6;
int32_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
int32_t rc_map_flightmode;
int32_t rc_fails_thr;
float rc_assist_th;
float rc_auto_th;
float rc_rattitude_th;
float rc_posctl_th;
float rc_return_th;
float rc_loiter_th;
float rc_acro_th;
float rc_offboard_th;
float rc_killswitch_th;
float rc_armswitch_th;
float rc_trans_th;
float rc_gear_th;
float rc_stab_th;
float rc_man_th;
bool rc_assist_inv;
bool rc_auto_inv;
bool rc_rattitude_inv;
bool rc_posctl_inv;
bool rc_return_inv;
bool rc_loiter_inv;
bool rc_acro_inv;
bool rc_offboard_inv;
bool rc_killswitch_inv;
bool rc_armswitch_inv;
bool rc_trans_inv;
bool rc_gear_inv;
bool rc_stab_inv;
bool rc_man_inv;
float rc_flt_smp_rate;
float rc_flt_cutoff;
};
struct ParameterHandles {
param_t min[RC_MAX_CHAN_COUNT];
param_t trim[RC_MAX_CHAN_COUNT];
param_t max[RC_MAX_CHAN_COUNT];
param_t rev[RC_MAX_CHAN_COUNT];
param_t dz[RC_MAX_CHAN_COUNT];
param_t rc_map_roll;
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
param_t rc_map_failsafe;
param_t rc_map_mode_sw;
param_t rc_map_return_sw;
param_t rc_map_rattitude_sw;
param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
param_t rc_map_acro_sw;
param_t rc_map_offboard_sw;
param_t rc_map_kill_sw;
param_t rc_map_arm_sw;
param_t rc_map_trans_sw;
param_t rc_map_gear_sw;
param_t rc_map_flaps;
param_t rc_map_stab_sw;
param_t rc_map_man_sw;
param_t rc_map_aux1;
param_t rc_map_aux2;
param_t rc_map_aux3;
param_t rc_map_aux4;
param_t rc_map_aux5;
param_t rc_map_aux6;
param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound
to a RC channel, equivalent float values in the
_parameters struct are not existing
because these parameters are never read. */
param_t rc_map_flightmode;
param_t rc_fails_thr;
param_t rc_assist_th;
param_t rc_auto_th;
param_t rc_rattitude_th;
param_t rc_posctl_th;
param_t rc_return_th;
param_t rc_loiter_th;
param_t rc_acro_th;
param_t rc_offboard_th;
param_t rc_killswitch_th;
param_t rc_armswitch_th;
param_t rc_trans_th;
param_t rc_gear_th;
param_t rc_stab_th;
param_t rc_man_th;
param_t rc_flt_smp_rate;
param_t rc_flt_cutoff;
};
/**
* initialize ParameterHandles struct
*/
void initialize_parameter_handles(ParameterHandles &parameter_handles);
/**
* Read out the parameters using the handles into the parameters struct.
* @return 0 on success, <0 on error
*/
int update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters);
} /* namespace RCUpdate */

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
* Copyright (c) 2016-2019 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
@ -39,18 +39,53 @@
#include "rc_update.h"
using namespace sensors;
#include "parameters.h"
RCUpdate::RCUpdate(const Parameters &parameters)
: _parameters(parameters),
_filter_roll(50.0f, 10.f), /* get replaced by parameter */
_filter_pitch(50.0f, 10.f),
_filter_yaw(50.0f, 10.f),
_filter_throttle(50.0f, 10.f)
namespace RCUpdate
{
RCUpdate::RCUpdate() :
ModuleParams(nullptr),
WorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME)),
_filter_roll(50.0f, 10.f), /* get replaced by parameter */
_filter_pitch(50.0f, 10.f),
_filter_yaw(50.0f, 10.f),
_filter_throttle(50.0f, 10.f)
{
initialize_parameter_handles(_parameter_handles);
rc_parameter_map_poll(true /* forced */);
parameters_updated();
}
void RCUpdate::update_rc_functions()
RCUpdate::~RCUpdate()
{
perf_free(_loop_perf);
}
bool
RCUpdate::init()
{
if (!_input_rc_sub.registerCallback()) {
PX4_ERR("input_rc callback registration failed!");
return false;
}
return true;
}
void
RCUpdate::parameters_updated()
{
/* read the parameter values into _parameters */
update_parameters(_parameter_handles, _parameters);
update_rc_functions();
}
void
RCUpdate::update_rc_functions()
{
/* update RC function mappings */
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_THROTTLE] = _parameters.rc_map_throttle - 1;
@ -97,9 +132,9 @@ void RCUpdate::update_rc_functions()
}
void
RCUpdate::rc_parameter_map_poll(ParameterHandles &parameter_handles, bool forced)
RCUpdate::rc_parameter_map_poll(bool forced)
{
if (_rc_parameter_map_sub.updated()) {
if (_rc_parameter_map_sub.updated() || forced) {
_rc_parameter_map_sub.copy(&_rc_parameter_map);
/* update parameter handles to which the RC channels are mapped */
@ -113,10 +148,10 @@ RCUpdate::rc_parameter_map_poll(ParameterHandles &parameter_handles, bool forced
/* Set the handle by index if the index is set, otherwise use the id */
if (_rc_parameter_map.param_index[i] >= 0) {
parameter_handles.rc_param[i] = param_for_used_index((unsigned)_rc_parameter_map.param_index[i]);
_parameter_handles.rc_param[i] = param_for_used_index((unsigned)_rc_parameter_map.param_index[i]);
} else {
parameter_handles.rc_param[i] = param_find(&_rc_parameter_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]);
_parameter_handles.rc_param[i] = param_find(&_rc_parameter_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]);
}
}
@ -188,7 +223,7 @@ RCUpdate::get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv)
}
void
RCUpdate::set_params_from_rc(const ParameterHandles &parameter_handles)
RCUpdate::set_params_from_rc()
{
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
if (_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
@ -207,21 +242,42 @@ RCUpdate::set_params_from_rc(const ParameterHandles &parameter_handles)
float param_val = math::constrain(
_rc_parameter_map.value0[i] + _rc_parameter_map.scale[i] * rc_val,
_rc_parameter_map.value_min[i], _rc_parameter_map.value_max[i]);
param_set(parameter_handles.rc_param[i], &param_val);
param_set(_parameter_handles.rc_param[i], &param_val);
}
}
}
void
RCUpdate::rc_poll(const ParameterHandles &parameter_handles)
RCUpdate::Run()
{
if (_rc_sub.updated()) {
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
input_rc_s rc_input{};
_rc_sub.copy(&rc_input);
if (should_exit()) {
_input_rc_sub.unregisterCallback();
exit_and_cleanup();
return;
}
perf_begin(_loop_perf);
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// update parameters from storage
updateParams();
parameters_updated();
}
rc_parameter_map_poll();
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
input_rc_s rc_input;
if (_input_rc_sub.copy(&rc_input)) {
/* detect RC signal loss */
bool signal_lost;
bool signal_lost = true;
/* check flags and require at least four channels to consider the signal valid */
if (rc_input.rc_lost || rc_input.rc_failsafe || rc_input.channel_count < 4) {
@ -422,9 +478,83 @@ RCUpdate::rc_poll(const ParameterHandles &parameter_handles)
/* Update parameters from RC Channels (tuning with RC) if activated */
if (hrt_elapsed_time(&_last_rc_to_param_map_time) > 1e6) {
set_params_from_rc(parameter_handles);
set_params_from_rc();
_last_rc_to_param_map_time = hrt_absolute_time();
}
}
}
perf_end(_loop_perf);
}
int
RCUpdate::task_spawn(int argc, char *argv[])
{
RCUpdate *instance = new RCUpdate();
if (instance) {
_object.store(instance);
_task_id = task_id_is_work_queue;
if (instance->init()) {
return PX4_OK;
}
} else {
PX4_ERR("alloc failed");
}
delete instance;
_object.store(nullptr);
_task_id = -1;
return PX4_ERROR;
}
int
RCUpdate::print_status()
{
PX4_INFO("Running");
perf_print_counter(_loop_perf);
return 0;
}
int
RCUpdate::custom_command(int argc, char *argv[])
{
return print_usage("unknown command");
}
int
RCUpdate::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
The rc_update module handles RC channel mapping: read the raw input channels (`input_rc`),
then apply the calibration, map the RC channels to the configured channels & mode switches,
low-pass filter, and then publish as `rc_channels` and `manual_control_setpoint`.
### Implementation
To reduce control latency, the module is scheduled on input_rc publications.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("rc_update", "system");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}
} // namespace RCUpdate
extern "C" __EXPORT int rc_update_main(int argc, char *argv[])
{
return RCUpdate::RCUpdate::main(argc, argv);
}

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
* Copyright (c) 2016-2019 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
@ -41,18 +41,27 @@
#include "parameters.h"
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_work_queue/WorkItem.hpp>
#include <drivers/drv_hrt.h>
#include <mathlib/mathlib.h>
#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/mathlib/mathlib.h>
#include <lib/mathlib/math/filter/LowPassFilter2p.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/rc_parameter_map.h>
#include <uORB/topics/parameter_update.h>
namespace sensors
namespace RCUpdate
{
/**
@ -60,31 +69,43 @@ namespace sensors
*
* Handling of RC updates
*/
class RCUpdate
class RCUpdate : public ModuleBase<RCUpdate>, public ModuleParams, public px4::WorkItem
{
public:
/**
* @param parameters parameter values. These do not have to be initialized when constructing this object.
* Only when calling init(), they have to be initialized.
*/
RCUpdate(const Parameters &parameters);
RCUpdate();
~RCUpdate() override;
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase */
static int custom_command(int argc, char *argv[]);
/** @see ModuleBase */
static int print_usage(const char *reason = nullptr);
void Run() override;
bool init();
/** @see ModuleBase::print_status() */
int print_status() override;
private:
/**
* Check for changes in rc_parameter_map
*/
void rc_parameter_map_poll(ParameterHandles &parameter_handles, bool forced = false);
void rc_parameter_map_poll(bool forced = false);
/**
* update the RC functions. Call this when the parameters change.
*/
void update_rc_functions();
void update_rc_functions();
/**
* Gather and publish RC input data.
* Update our local parameter cache.
*/
void rc_poll(const ParameterHandles &parameter_handles);
private:
void parameters_updated();
/**
* Get and limit value for specified RC function. Returns NAN if not mapped.
@ -103,10 +124,16 @@ private:
*
* @param
*/
void set_params_from_rc(const ParameterHandles &parameter_handles);
void set_params_from_rc();
perf_counter_t _loop_perf; /**< loop performance counter */
uORB::Subscription _rc_sub{ORB_ID(input_rc)}; /**< raw rc channels data subscription */
Parameters _parameters{}; /**< local copies of interesting parameters */
ParameterHandles _parameter_handles{}; /**< handles for interesting parameters */
uORB::SubscriptionCallbackWorkItem _input_rc_sub{this, ORB_ID(input_rc)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; /**< notification of parameter updates */
uORB::Subscription _rc_parameter_map_sub{ORB_ID(rc_parameter_map)}; /**< rc parameter map subscription */
uORB::Publication<rc_channels_s> _rc_pub{ORB_ID(rc_channels)}; /**< raw r/c control topic */
@ -119,8 +146,6 @@ private:
rc_parameter_map_s _rc_parameter_map {};
float _param_rc_values[rc_parameter_map_s::RC_PARAM_MAP_NCHAN] {}; /**< parameter values for RC control */
const Parameters &_parameters;
hrt_abstime _last_rc_to_param_map_time = 0;
math::LowPassFilter2p _filter_roll; /**< filters for the main 4 stick inputs */
@ -132,4 +157,4 @@ private:
} /* namespace sensors */
} /* namespace RCUpdate */

View File

@ -40,7 +40,6 @@ px4_add_module(
PRIORITY "SCHED_PRIORITY_MAX-5"
SRCS
voted_sensors_update.cpp
rc_update.cpp
sensors.cpp
parameters.cpp
temperature_compensation.cpp

View File

@ -44,96 +44,6 @@ namespace sensors
void initialize_parameter_handles(ParameterHandles &parameter_handles)
{
/* basic r/c parameters */
for (unsigned i = 0; i < RC_MAX_CHAN_COUNT; i++) {
char nbuf[16];
/* min values */
sprintf(nbuf, "RC%d_MIN", i + 1);
parameter_handles.min[i] = param_find(nbuf);
/* trim values */
sprintf(nbuf, "RC%d_TRIM", i + 1);
parameter_handles.trim[i] = param_find(nbuf);
/* max values */
sprintf(nbuf, "RC%d_MAX", i + 1);
parameter_handles.max[i] = param_find(nbuf);
/* channel reverse */
sprintf(nbuf, "RC%d_REV", i + 1);
parameter_handles.rev[i] = param_find(nbuf);
/* channel deadzone */
sprintf(nbuf, "RC%d_DZ", i + 1);
parameter_handles.dz[i] = param_find(nbuf);
}
/* mandatory input switched, mapped to channels 1-4 per default */
parameter_handles.rc_map_roll = param_find("RC_MAP_ROLL");
parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW");
parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
parameter_handles.rc_map_return_sw = param_find("RC_MAP_RETURN_SW");
parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
parameter_handles.rc_map_rattitude_sw = param_find("RC_MAP_RATT_SW");
parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
parameter_handles.rc_map_kill_sw = param_find("RC_MAP_KILL_SW");
parameter_handles.rc_map_arm_sw = param_find("RC_MAP_ARM_SW");
parameter_handles.rc_map_trans_sw = param_find("RC_MAP_TRANS_SW");
parameter_handles.rc_map_gear_sw = param_find("RC_MAP_GEAR_SW");
parameter_handles.rc_map_stab_sw = param_find("RC_MAP_STAB_SW");
parameter_handles.rc_map_man_sw = param_find("RC_MAP_MAN_SW");
parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
parameter_handles.rc_map_aux3 = param_find("RC_MAP_AUX3");
parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
parameter_handles.rc_map_aux6 = param_find("RC_MAP_AUX6");
/* RC to parameter mapping for changing parameters with RC */
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
char name[rc_parameter_map_s::PARAM_ID_LEN];
snprintf(name, rc_parameter_map_s::PARAM_ID_LEN, "RC_MAP_PARAM%d",
i + 1); // shifted by 1 because param name starts at 1
parameter_handles.rc_map_param[i] = param_find(name);
}
parameter_handles.rc_map_flightmode = param_find("RC_MAP_FLTMODE");
/* RC thresholds */
parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
parameter_handles.rc_rattitude_th = param_find("RC_RATT_TH");
parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
parameter_handles.rc_killswitch_th = param_find("RC_KILLSWITCH_TH");
parameter_handles.rc_armswitch_th = param_find("RC_ARMSWITCH_TH");
parameter_handles.rc_trans_th = param_find("RC_TRANS_TH");
parameter_handles.rc_gear_th = param_find("RC_GEAR_TH");
parameter_handles.rc_stab_th = param_find("RC_STAB_TH");
parameter_handles.rc_man_th = param_find("RC_MAN_TH");
/* RC low pass filter configuration */
parameter_handles.rc_flt_smp_rate = param_find("RC_FLT_SMP_RATE");
parameter_handles.rc_flt_cutoff = param_find("RC_FLT_CUTOFF");
/* Differential pressure offset */
parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF");
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
@ -155,10 +65,6 @@ void initialize_parameter_handles(ParameterHandles &parameter_handles)
parameter_handles.air_tube_length = param_find("CAL_AIR_TUBELEN");
parameter_handles.air_tube_diameter_mm = param_find("CAL_AIR_TUBED_MM");
// These are parameters for which QGroundControl always expects to be returned in a list request.
// We do a param_find here to force them into the list.
(void)param_find("RC_CHAN_CNT");
(void)param_find("BAT_V_DIV");
(void)param_find("BAT_A_PER_V");
@ -187,186 +93,8 @@ void initialize_parameter_handles(ParameterHandles &parameter_handles)
(void)param_find("SYS_CAL_TMIN");
}
int update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters)
void update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters)
{
bool rc_valid = true;
float tmpScaleFactor = 0.0f;
float tmpRevFactor = 0.0f;
int ret = PX4_OK;
/* rc values */
for (unsigned int i = 0; i < RC_MAX_CHAN_COUNT; i++) {
param_get(parameter_handles.min[i], &(parameters.min[i]));
param_get(parameter_handles.trim[i], &(parameters.trim[i]));
param_get(parameter_handles.max[i], &(parameters.max[i]));
param_get(parameter_handles.rev[i], &(parameters.rev[i]));
param_get(parameter_handles.dz[i], &(parameters.dz[i]));
tmpScaleFactor = (1.0f / ((parameters.max[i] - parameters.min[i]) / 2.0f) * parameters.rev[i]);
tmpRevFactor = tmpScaleFactor * parameters.rev[i];
/* handle blowup in the scaling factor calculation */
if (!PX4_ISFINITE(tmpScaleFactor) ||
(tmpRevFactor < 0.000001f) ||
(tmpRevFactor > 0.2f)) {
PX4_WARN("RC chan %u not sane, scaling: %8.6f, rev: %d", i, (double)tmpScaleFactor, (int)(parameters.rev[i]));
/* scaling factors do not make sense, lock them down */
parameters.scaling_factor[i] = 0.0f;
rc_valid = false;
} else {
parameters.scaling_factor[i] = tmpScaleFactor;
}
}
/* handle wrong values */
if (!rc_valid) {
PX4_ERR("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
}
const char *paramerr = "FAIL PARM LOAD";
/* channel mapping */
if (param_get(parameter_handles.rc_map_roll, &(parameters.rc_map_roll)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_pitch, &(parameters.rc_map_pitch)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_yaw, &(parameters.rc_map_yaw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_throttle, &(parameters.rc_map_throttle)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_failsafe, &(parameters.rc_map_failsafe)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_mode_sw, &(parameters.rc_map_mode_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_return_sw, &(parameters.rc_map_return_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_rattitude_sw, &(parameters.rc_map_rattitude_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_posctl_sw, &(parameters.rc_map_posctl_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_loiter_sw, &(parameters.rc_map_loiter_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_acro_sw, &(parameters.rc_map_acro_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_offboard_sw, &(parameters.rc_map_offboard_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_kill_sw, &(parameters.rc_map_kill_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_arm_sw, &(parameters.rc_map_arm_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_trans_sw, &(parameters.rc_map_trans_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_flaps, &(parameters.rc_map_flaps)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_gear_sw, &(parameters.rc_map_gear_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_stab_sw, &(parameters.rc_map_stab_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
if (param_get(parameter_handles.rc_map_man_sw, &(parameters.rc_map_man_sw)) != OK) {
PX4_WARN("%s", paramerr);
}
param_get(parameter_handles.rc_map_aux1, &(parameters.rc_map_aux1));
param_get(parameter_handles.rc_map_aux2, &(parameters.rc_map_aux2));
param_get(parameter_handles.rc_map_aux3, &(parameters.rc_map_aux3));
param_get(parameter_handles.rc_map_aux4, &(parameters.rc_map_aux4));
param_get(parameter_handles.rc_map_aux5, &(parameters.rc_map_aux5));
param_get(parameter_handles.rc_map_aux6, &(parameters.rc_map_aux6));
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
param_get(parameter_handles.rc_map_param[i], &(parameters.rc_map_param[i]));
}
param_get(parameter_handles.rc_map_flightmode, &(parameters.rc_map_flightmode));
param_get(parameter_handles.rc_fails_thr, &(parameters.rc_fails_thr));
param_get(parameter_handles.rc_assist_th, &(parameters.rc_assist_th));
parameters.rc_assist_inv = (parameters.rc_assist_th < 0);
parameters.rc_assist_th = fabsf(parameters.rc_assist_th);
param_get(parameter_handles.rc_auto_th, &(parameters.rc_auto_th));
parameters.rc_auto_inv = (parameters.rc_auto_th < 0);
parameters.rc_auto_th = fabsf(parameters.rc_auto_th);
param_get(parameter_handles.rc_rattitude_th, &(parameters.rc_rattitude_th));
parameters.rc_rattitude_inv = (parameters.rc_rattitude_th < 0);
parameters.rc_rattitude_th = fabsf(parameters.rc_rattitude_th);
param_get(parameter_handles.rc_posctl_th, &(parameters.rc_posctl_th));
parameters.rc_posctl_inv = (parameters.rc_posctl_th < 0);
parameters.rc_posctl_th = fabsf(parameters.rc_posctl_th);
param_get(parameter_handles.rc_return_th, &(parameters.rc_return_th));
parameters.rc_return_inv = (parameters.rc_return_th < 0);
parameters.rc_return_th = fabsf(parameters.rc_return_th);
param_get(parameter_handles.rc_loiter_th, &(parameters.rc_loiter_th));
parameters.rc_loiter_inv = (parameters.rc_loiter_th < 0);
parameters.rc_loiter_th = fabsf(parameters.rc_loiter_th);
param_get(parameter_handles.rc_acro_th, &(parameters.rc_acro_th));
parameters.rc_acro_inv = (parameters.rc_acro_th < 0);
parameters.rc_acro_th = fabsf(parameters.rc_acro_th);
param_get(parameter_handles.rc_offboard_th, &(parameters.rc_offboard_th));
parameters.rc_offboard_inv = (parameters.rc_offboard_th < 0);
parameters.rc_offboard_th = fabsf(parameters.rc_offboard_th);
param_get(parameter_handles.rc_killswitch_th, &(parameters.rc_killswitch_th));
parameters.rc_killswitch_inv = (parameters.rc_killswitch_th < 0);
parameters.rc_killswitch_th = fabsf(parameters.rc_killswitch_th);
param_get(parameter_handles.rc_armswitch_th, &(parameters.rc_armswitch_th));
parameters.rc_armswitch_inv = (parameters.rc_armswitch_th < 0);
parameters.rc_armswitch_th = fabsf(parameters.rc_armswitch_th);
param_get(parameter_handles.rc_trans_th, &(parameters.rc_trans_th));
parameters.rc_trans_inv = (parameters.rc_trans_th < 0);
parameters.rc_trans_th = fabsf(parameters.rc_trans_th);
param_get(parameter_handles.rc_gear_th, &(parameters.rc_gear_th));
parameters.rc_gear_inv = (parameters.rc_gear_th < 0);
parameters.rc_gear_th = fabsf(parameters.rc_gear_th);
param_get(parameter_handles.rc_stab_th, &(parameters.rc_stab_th));
parameters.rc_stab_inv = (parameters.rc_stab_th < 0);
parameters.rc_stab_th = fabsf(parameters.rc_stab_th);
param_get(parameter_handles.rc_man_th, &(parameters.rc_man_th));
parameters.rc_man_inv = (parameters.rc_man_th < 0);
parameters.rc_man_th = fabsf(parameters.rc_man_th);
param_get(parameter_handles.rc_flt_smp_rate, &(parameters.rc_flt_smp_rate));
parameters.rc_flt_smp_rate = math::max(1.0f, parameters.rc_flt_smp_rate);
param_get(parameter_handles.rc_flt_cutoff, &(parameters.rc_flt_cutoff));
/* make sure the filter is in its stable region -> fc < fs/2 */
parameters.rc_flt_cutoff = math::min(parameters.rc_flt_cutoff, (parameters.rc_flt_smp_rate / 2) - 1.f);
/* Airspeed offset */
param_get(parameter_handles.diff_pres_offset_pa, &(parameters.diff_pres_offset_pa));
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
@ -384,8 +112,6 @@ int update_parameters(const ParameterHandles &parameter_handles, Parameters &par
param_get(parameter_handles.air_cmodel, &parameters.air_cmodel);
param_get(parameter_handles.air_tube_length, &parameters.air_tube_length);
param_get(parameter_handles.air_tube_diameter_mm, &parameters.air_tube_diameter_mm);
return ret;
}
} /* namespace sensors */

View File

@ -40,29 +40,13 @@
*
* @author Beat Kueng <beat-kueng@gmx.net>
*/
#include <px4_platform_common/px4_config.h>
#include <drivers/drv_rc_input.h>
#include <parameters/param.h>
#include <mathlib/mathlib.h>
#include <uORB/topics/rc_parameter_map.h>
#include <uORB/topics/input_rc.h>
#include <lib/parameters/param.h>
namespace sensors
{
static const unsigned RC_MAX_CHAN_COUNT =
input_rc_s::RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
struct Parameters {
float min[RC_MAX_CHAN_COUNT];
float trim[RC_MAX_CHAN_COUNT];
float max[RC_MAX_CHAN_COUNT];
float rev[RC_MAX_CHAN_COUNT];
float dz[RC_MAX_CHAN_COUNT];
float scaling_factor[RC_MAX_CHAN_COUNT];
float diff_pres_offset_pa;
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
float diff_pres_analog_scale;
@ -72,72 +56,6 @@ struct Parameters {
float board_offset[3];
int32_t rc_map_roll;
int32_t rc_map_pitch;
int32_t rc_map_yaw;
int32_t rc_map_throttle;
int32_t rc_map_failsafe;
int32_t rc_map_mode_sw;
int32_t rc_map_return_sw;
int32_t rc_map_rattitude_sw;
int32_t rc_map_posctl_sw;
int32_t rc_map_loiter_sw;
int32_t rc_map_acro_sw;
int32_t rc_map_offboard_sw;
int32_t rc_map_kill_sw;
int32_t rc_map_arm_sw;
int32_t rc_map_trans_sw;
int32_t rc_map_gear_sw;
int32_t rc_map_stab_sw;
int32_t rc_map_man_sw;
int32_t rc_map_flaps;
int32_t rc_map_aux1;
int32_t rc_map_aux2;
int32_t rc_map_aux3;
int32_t rc_map_aux4;
int32_t rc_map_aux5;
int32_t rc_map_aux6;
int32_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
int32_t rc_map_flightmode;
int32_t rc_fails_thr;
float rc_assist_th;
float rc_auto_th;
float rc_rattitude_th;
float rc_posctl_th;
float rc_return_th;
float rc_loiter_th;
float rc_acro_th;
float rc_offboard_th;
float rc_killswitch_th;
float rc_armswitch_th;
float rc_trans_th;
float rc_gear_th;
float rc_stab_th;
float rc_man_th;
bool rc_assist_inv;
bool rc_auto_inv;
bool rc_rattitude_inv;
bool rc_posctl_inv;
bool rc_return_inv;
bool rc_loiter_inv;
bool rc_acro_inv;
bool rc_offboard_inv;
bool rc_killswitch_inv;
bool rc_armswitch_inv;
bool rc_trans_inv;
bool rc_gear_inv;
bool rc_stab_inv;
bool rc_man_inv;
float rc_flt_smp_rate;
float rc_flt_cutoff;
float baro_qnh;
int32_t air_cmodel;
@ -146,72 +64,11 @@ struct Parameters {
};
struct ParameterHandles {
param_t min[RC_MAX_CHAN_COUNT];
param_t trim[RC_MAX_CHAN_COUNT];
param_t max[RC_MAX_CHAN_COUNT];
param_t rev[RC_MAX_CHAN_COUNT];
param_t dz[RC_MAX_CHAN_COUNT];
param_t diff_pres_offset_pa;
#ifdef ADC_AIRSPEED_VOLTAGE_CHANNEL
param_t diff_pres_analog_scale;
#endif /* ADC_AIRSPEED_VOLTAGE_CHANNEL */
param_t rc_map_roll;
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
param_t rc_map_failsafe;
param_t rc_map_mode_sw;
param_t rc_map_return_sw;
param_t rc_map_rattitude_sw;
param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
param_t rc_map_acro_sw;
param_t rc_map_offboard_sw;
param_t rc_map_kill_sw;
param_t rc_map_arm_sw;
param_t rc_map_trans_sw;
param_t rc_map_gear_sw;
param_t rc_map_flaps;
param_t rc_map_stab_sw;
param_t rc_map_man_sw;
param_t rc_map_aux1;
param_t rc_map_aux2;
param_t rc_map_aux3;
param_t rc_map_aux4;
param_t rc_map_aux5;
param_t rc_map_aux6;
param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound
to a RC channel, equivalent float values in the
_parameters struct are not existing
because these parameters are never read. */
param_t rc_map_flightmode;
param_t rc_fails_thr;
param_t rc_assist_th;
param_t rc_auto_th;
param_t rc_rattitude_th;
param_t rc_posctl_th;
param_t rc_return_th;
param_t rc_loiter_th;
param_t rc_acro_th;
param_t rc_offboard_th;
param_t rc_killswitch_th;
param_t rc_armswitch_th;
param_t rc_trans_th;
param_t rc_gear_th;
param_t rc_stab_th;
param_t rc_man_th;
param_t rc_flt_smp_rate;
param_t rc_flt_cutoff;
param_t board_rotation;
param_t board_offset[3];
@ -234,6 +91,6 @@ void initialize_parameter_handles(ParameterHandles &parameter_handles);
* Read out the parameters using the handles into the parameters struct.
* @return 0 on success, <0 on error
*/
int update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters);
void update_parameters(const ParameterHandles &parameter_handles, Parameters &parameters);
} /* namespace sensors */

View File

@ -41,53 +41,36 @@
* @author Beat Küng <beat-kueng@gmx.net>
*/
#include <board_config.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/time.h>
#include <fcntl.h>
#include <poll.h>
#include <unistd.h>
#include <stdlib.h>
#include <string.h>
#include <stdbool.h>
#include <stdio.h>
#include <errno.h>
#include <math.h>
#include <mathlib/mathlib.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_adc.h>
#include <drivers/drv_airspeed.h>
#include <airspeed/airspeed.h>
#include <parameters/param.h>
#include <systemlib/err.h>
#include <perf/perf_counter.h>
#include <conversion/rotation.h>
#include <uORB/uORB.h>
#include <drivers/drv_hrt.h>
#include <lib/airspeed/airspeed.h>
#include <lib/conversion/rotation.h>
#include <lib/mathlib/mathlib.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/time.h>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/sensor_preflight.h>
#include <uORB/topics/vehicle_air_data.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_magnetometer.h>
#include <DevMgr.hpp>
#include "parameters.h"
#include "rc_update.h"
#include "voted_sensors_update.h"
#include "vehicle_acceleration/VehicleAcceleration.hpp"
@ -102,15 +85,6 @@ using namespace time_literals;
* subtract 5 degrees in an attempt to account for the electrical upheating of the PCB
*/
#define PCB_TEMP_ESTIMATE_DEG 5.0f
#define STICK_ON_OFF_LIMIT 0.75f
/**
* Sensor app start / stop handling function
*
* @ingroup apps
*/
extern "C" __EXPORT int sensors_main(int argc, char *argv[]);
class Sensors : public ModuleBase<Sensors>, public ModuleParams
{
public:
@ -166,7 +140,6 @@ private:
Parameters _parameters{}; /**< local copies of interesting parameters */
ParameterHandles _parameter_handles{}; /**< handles for interesting parameters */
RCUpdate _rc_update;
VotedSensorsUpdate _voted_sensors_update;
@ -211,7 +184,6 @@ Sensors::Sensors(bool hil_enabled) :
ModuleParams(nullptr),
_hil_enabled(hil_enabled),
_loop_perf(perf_alloc(PC_ELAPSED, "sensors")),
_rc_update(_parameters),
_voted_sensors_update(_parameters, hil_enabled)
{
initialize_parameter_handles(_parameter_handles);
@ -237,16 +209,11 @@ Sensors::parameters_update()
}
/* read the parameter values into _parameters */
int ret = update_parameters(_parameter_handles, _parameters);
update_parameters(_parameter_handles, _parameters);
if (ret) {
return ret;
}
_rc_update.update_rc_functions();
_voted_sensors_update.parametersUpdate();
return ret;
return PX4_OK;
}
int
@ -438,8 +405,6 @@ Sensors::run()
diff_pres_poll(airdata);
_rc_update.rc_parameter_map_poll(_parameter_handles, true /* forced */);
/* wakeup source */
px4_pollfd_struct_t poll_fds = {};
poll_fds.events = POLLIN;
@ -532,14 +497,8 @@ Sensors::run()
/* check parameters for updates */
parameter_update_poll();
/* check rc parameter map for updates */
_rc_update.rc_parameter_map_poll(_parameter_handles);
}
/* Look for new r/c input data */
_rc_update.rc_poll(_parameter_handles);
perf_end(_loop_perf);
}
@ -599,9 +558,6 @@ The provided functionality includes:
If there are multiple of the same type, do voting and failover handling.
Then apply the board rotation and temperature calibration (if enabled). And finally publish the data; one of the
topics is `sensor_combined`, used by many parts of the system.
- Do RC channel mapping: read the raw input channels (`input_rc`), then apply the calibration, map the RC channels
to the configured channels & mode switches, low-pass filter, and then publish as `rc_channels` and
`manual_control_setpoint`.
- Make sure the sensor drivers get the updated calibration parameters (scale & offset) when the parameters change or
on startup. The sensor drivers use the ioctl interface for parameter updates. For this to work properly, the
sensor drivers must already be running when `sensors` is started.
@ -653,7 +609,7 @@ Sensors *Sensors::instantiate(int argc, char *argv[])
return new Sensors(hil_enabled);
}
int sensors_main(int argc, char *argv[])
extern "C" __EXPORT int sensors_main(int argc, char *argv[])
{
return Sensors::main(argc, argv);
}