mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-20 08:00:34 +08:00
Compare commits
3 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| a10f775a70 | |||
| d6d2b41c39 | |||
| 9dfb761504 |
@@ -12,7 +12,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -14,7 +14,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -16,7 +16,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -14,7 +14,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -14,7 +14,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -26,7 +26,7 @@ param set-default NPFG_PERIOD 12
|
||||
param set-default FW_PR_P 0.9
|
||||
param set-default FW_PR_FF 0.5
|
||||
param set-default FW_PR_I 0.5
|
||||
param set-default TRIM_PITCH -0.15
|
||||
param set-default FW_TRIM_PITCH -0.15
|
||||
|
||||
param set-default FW_PSP_OFF 2
|
||||
param set-default FW_P_LIM_MIN -15
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2024 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
|
||||
@@ -73,5 +73,26 @@ param_modify_on_import_ret param_modify_on_import(bson_node_t node)
|
||||
}
|
||||
}
|
||||
|
||||
// 2024-04-03: translate TRIM_ROLL/PITCH/YAW-> FW_TRIM_ROLL/PITCH/YAW
|
||||
{
|
||||
if (strcmp("TRIM_ROLL", node->name) == 0) {
|
||||
strcpy(node->name, "FW_TRIM_ROLL");
|
||||
PX4_INFO("copying %s -> %s", "TRIM_ROLL", "FW_TRIM_ROLL");
|
||||
return param_modify_on_import_ret::PARAM_MODIFIED;
|
||||
}
|
||||
|
||||
if (strcmp("TRIM_PITCH", node->name) == 0) {
|
||||
strcpy(node->name, "FW_TRIM_PITCH");
|
||||
PX4_INFO("copying %s -> %s", "TRIM_PITCH", "FW_TRIM_PITCH");
|
||||
return param_modify_on_import_ret::PARAM_MODIFIED;
|
||||
}
|
||||
|
||||
if (strcmp("TRIM_YAW", node->name) == 0) {
|
||||
strcpy(node->name, "FW_TRIM_YAW");
|
||||
PX4_INFO("copying %s -> %s", "TRIM_YAW", "FW_TRIM_YAW");
|
||||
return param_modify_on_import_ret::PARAM_MODIFIED;
|
||||
}
|
||||
}
|
||||
|
||||
return param_modify_on_import_ret::PARAM_NOT_MODIFIED;
|
||||
}
|
||||
|
||||
@@ -57,7 +57,6 @@ px4_add_module(
|
||||
level_calibration.cpp
|
||||
lm_fit.cpp
|
||||
mag_calibration.cpp
|
||||
rc_calibration.cpp
|
||||
Safety.cpp
|
||||
UserModeIntention.cpp
|
||||
worker_thread.cpp
|
||||
|
||||
@@ -1284,8 +1284,9 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||
} else if ((int)(cmd.param4) == 2) {
|
||||
/* RC trim calibration */
|
||||
answer_command(cmd, vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED);
|
||||
_vehicle_status.calibration_enabled = true;
|
||||
_worker_thread.startTask(WorkerThread::Request::RCTrimCalibration);
|
||||
mavlink_log_critical(&_mavlink_log_pub, "RC trim calibration is deprecated\t");
|
||||
events::send(events::ID("commander_rc_trim_cal_denied"), events::Log::Critical,
|
||||
"RC trim calibration is deprecated");
|
||||
|
||||
} else if ((int)(cmd.param5) == 1) {
|
||||
/* accelerometer calibration */
|
||||
|
||||
@@ -41,48 +41,6 @@
|
||||
* @author Julian Oes <julian@px4.io>
|
||||
*/
|
||||
|
||||
/**
|
||||
* Roll trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group Radio Calibration
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
|
||||
|
||||
/**
|
||||
* Pitch trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group Radio Calibration
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
|
||||
|
||||
/**
|
||||
* Yaw trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group Radio Calibration
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
|
||||
|
||||
/**
|
||||
* GCS connection loss time threshold
|
||||
*
|
||||
|
||||
@@ -1,110 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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 rc_calibration.cpp
|
||||
* Remote Control calibration routine
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/events.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/time.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
|
||||
#include "rc_calibration.h"
|
||||
#include "commander_helper.h"
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <systemlib/mavlink_log.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
int do_trim_calibration(orb_advert_t *mavlink_log_pub)
|
||||
{
|
||||
uORB::Subscription manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
|
||||
px4_usleep(400000);
|
||||
manual_control_setpoint_s manual_control_setpoint{};
|
||||
bool changed = manual_control_setpoint_sub.updated();
|
||||
|
||||
if (!changed) {
|
||||
mavlink_log_critical(mavlink_log_pub, "no inputs, aborting\t");
|
||||
events::send(events::ID("commander_cal_no_inputs"), {events::Log::Error, events::LogInternal::Info},
|
||||
"No inputs, aborting RC trim calibration");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
manual_control_setpoint_sub.copy(&manual_control_setpoint);
|
||||
|
||||
/* load trim values which are active */
|
||||
float roll_trim_active;
|
||||
param_get(param_find("TRIM_ROLL"), &roll_trim_active);
|
||||
float pitch_trim_active;
|
||||
param_get(param_find("TRIM_PITCH"), &pitch_trim_active);
|
||||
float yaw_trim_active;
|
||||
param_get(param_find("TRIM_YAW"), &yaw_trim_active);
|
||||
|
||||
/* get manual control scale values */
|
||||
float roll_scale;
|
||||
param_get(param_find("FW_MAN_R_SC"), &roll_scale);
|
||||
float pitch_scale;
|
||||
param_get(param_find("FW_MAN_P_SC"), &pitch_scale);
|
||||
float yaw_scale;
|
||||
param_get(param_find("FW_MAN_Y_SC"), &yaw_scale);
|
||||
|
||||
/* set parameters: the new trim values are the combination of active trim values
|
||||
and the values coming from the remote control of the user
|
||||
*/
|
||||
float p = manual_control_setpoint.roll * roll_scale + roll_trim_active;
|
||||
int p1r = param_set(param_find("TRIM_ROLL"), &p);
|
||||
/*
|
||||
we explicitly swap sign here because the trim is added to the actuator controls
|
||||
which are moving in an inverse sense to manual pitch inputs
|
||||
*/
|
||||
p = -manual_control_setpoint.pitch * pitch_scale + pitch_trim_active;
|
||||
int p2r = param_set(param_find("TRIM_PITCH"), &p);
|
||||
p = manual_control_setpoint.yaw * yaw_scale + yaw_trim_active;
|
||||
int p3r = param_set(param_find("TRIM_YAW"), &p);
|
||||
|
||||
if (p1r != 0 || p2r != 0 || p3r != 0) {
|
||||
mavlink_log_critical(mavlink_log_pub, "TRIM: PARAM SET FAIL\t");
|
||||
events::send(events::ID("commander_cal_trim_param_set_failed"), events::Log::Critical,
|
||||
"RC trim calibration: failed to set parameters");
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
mavlink_log_info(mavlink_log_pub, "trim cal done\t");
|
||||
events::send(events::ID("commander_cal_trim_done"), events::Log::Info, "RC trim calibration completed");
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
@@ -1,47 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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 rc_calibration.h
|
||||
* Remote Control calibration routine
|
||||
*/
|
||||
|
||||
#ifndef RC_CALIBRATION_H_
|
||||
#define RC_CALIBRATION_H_
|
||||
|
||||
#include <stdint.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
int do_trim_calibration(orb_advert_t *mavlink_log_pub);
|
||||
|
||||
#endif /* RC_CALIBRATION_H_ */
|
||||
@@ -40,7 +40,6 @@
|
||||
#include "gyro_calibration.h"
|
||||
#include "level_calibration.h"
|
||||
#include "mag_calibration.h"
|
||||
#include "rc_calibration.h"
|
||||
|
||||
#include <px4_platform_common/events.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
@@ -115,10 +114,6 @@ void WorkerThread::threadEntry()
|
||||
_ret_value = do_mag_calibration(&_mavlink_log_pub);
|
||||
break;
|
||||
|
||||
case Request::RCTrimCalibration:
|
||||
_ret_value = do_trim_calibration(&_mavlink_log_pub);
|
||||
break;
|
||||
|
||||
case Request::AccelCalibration:
|
||||
_ret_value = do_accel_calibration(&_mavlink_log_pub);
|
||||
break;
|
||||
|
||||
@@ -51,7 +51,6 @@ public:
|
||||
enum class Request {
|
||||
GyroCalibration,
|
||||
MagCalibration,
|
||||
RCTrimCalibration,
|
||||
AccelCalibration,
|
||||
LevelCalibration,
|
||||
AccelCalibrationQuick,
|
||||
|
||||
@@ -200,9 +200,9 @@ private:
|
||||
(ParamFloat<px4::params::FW_YR_P>) _param_fw_yr_p,
|
||||
(ParamFloat<px4::params::FW_YR_D>) _param_fw_yr_d,
|
||||
|
||||
(ParamFloat<px4::params::TRIM_PITCH>) _param_trim_pitch,
|
||||
(ParamFloat<px4::params::TRIM_ROLL>) _param_trim_roll,
|
||||
(ParamFloat<px4::params::TRIM_YAW>) _param_trim_yaw,
|
||||
(ParamFloat<px4::params::FW_TRIM_PITCH>) _param_trim_pitch,
|
||||
(ParamFloat<px4::params::FW_TRIM_ROLL>) _param_trim_roll,
|
||||
(ParamFloat<px4::params::FW_TRIM_YAW>) _param_trim_yaw,
|
||||
|
||||
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man
|
||||
)
|
||||
|
||||
@@ -298,7 +298,7 @@ PARAM_DEFINE_INT32(FW_ARSP_SCALE_EN, 1);
|
||||
/**
|
||||
* Roll trim increment at minimum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.
|
||||
* This increment is added to FW_TRIM_ROLL when airspeed is FW_AIRSPD_MIN.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -311,7 +311,7 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_R_VMIN, 0.0f);
|
||||
/**
|
||||
* Pitch trim increment at minimum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.
|
||||
* This increment is added to FW_TRIM_PITCH when airspeed is FW_AIRSPD_MIN.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -324,7 +324,7 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_P_VMIN, 0.0f);
|
||||
/**
|
||||
* Yaw trim increment at minimum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.
|
||||
* This increment is added to FW_TRIM_YAW when airspeed is FW_AIRSPD_MIN.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -337,7 +337,7 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_Y_VMIN, 0.0f);
|
||||
/**
|
||||
* Roll trim increment at maximum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.
|
||||
* This increment is added to FW_TRIM_ROLL when airspeed is FW_AIRSPD_MAX.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -350,7 +350,7 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_R_VMAX, 0.0f);
|
||||
/**
|
||||
* Pitch trim increment at maximum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.
|
||||
* This increment is added to FW_TRIM_PITCH when airspeed is FW_AIRSPD_MAX.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -363,7 +363,7 @@ PARAM_DEFINE_FLOAT(FW_DTRIM_P_VMAX, 0.0f);
|
||||
/**
|
||||
* Yaw trim increment at maximum airspeed
|
||||
*
|
||||
* This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.
|
||||
* This increment is added to FW_TRIM_YAW when airspeed is FW_AIRSPD_MAX.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
@@ -454,3 +454,45 @@ PARAM_DEFINE_INT32(FW_SPOILERS_MAN, 0);
|
||||
* @group FW Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(FW_ACRO_YAW_EN, 0);
|
||||
|
||||
/**
|
||||
* Roll trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_TRIM_ROLL, 0.0f);
|
||||
|
||||
/**
|
||||
* Pitch trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_TRIM_PITCH, 0.0f);
|
||||
|
||||
/**
|
||||
* Yaw trim
|
||||
*
|
||||
* The trim value is the actuator control value the system needs
|
||||
* for straight and level flight.
|
||||
*
|
||||
* @group FW Rate Control
|
||||
* @min -0.5
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_TRIM_YAW, 0.0f);
|
||||
|
||||
Reference in New Issue
Block a user