mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
Merge pull request #2340 from PX4/pwm_setting_params
PWM setting params
This commit is contained in:
@@ -34,7 +34,9 @@ then
|
||||
param set PWM_MAIN_REV1 1
|
||||
fi
|
||||
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
set PWM_MIN p:PWM_MIN
|
||||
set PWM_MAX p:PWM_MAX
|
||||
|
||||
set MIXER caipi
|
||||
# Provide ESC a constant 1000 us pulse
|
||||
set PWM_OUT 4
|
||||
set PWM_DISARMED 1000
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -83,7 +83,7 @@ __BEGIN_DECLS
|
||||
/**
|
||||
* Highest maximum PWM in us
|
||||
*/
|
||||
#define PWM_HIGHEST_MAX 2100
|
||||
#define PWM_HIGHEST_MAX 2150
|
||||
|
||||
/**
|
||||
* Default maximum PWM in us
|
||||
|
||||
@@ -1401,3 +1401,110 @@ PARAM_DEFINE_INT32(RC_RSSI_PWM_MAX, 1000);
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_RSSI_PWM_MIN, 2000);
|
||||
|
||||
/**
|
||||
* Enable Lidar-Lite (LL40LS) pwm driver
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Sensor Enable
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 1000 for default or 900 to increase servo travel
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MIN, 1000);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 2000 for default or 2100 to increase servo travel
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAX, 2000);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* The main use of this parameter is to silence ESCs when they are disarmed.
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_DISARMED, 0);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 1000 for default or 900 to increase servo travel
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the MAIN outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* Set to 2000 for default or 2100 to increase servo travel
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for AUX outputs
|
||||
*
|
||||
* IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM
|
||||
* REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE
|
||||
* THE SYSTEM TO PUT CHANGES INTO EFFECT.
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* The main use of this parameter is to silence ESCs when they are disarmed.
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit microseconds
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DISARMED, 1000);
|
||||
|
||||
@@ -634,6 +634,12 @@ Sensors::Sensors() :
|
||||
(void)param_find("CAL_MAG2_ROT");
|
||||
(void)param_find("SYS_PARAM_VER");
|
||||
(void)param_find("SYS_AUTOSTART");
|
||||
(void)param_find("PWM_MIN");
|
||||
(void)param_find("PWM_MAX");
|
||||
(void)param_find("PWM_DISARMED");
|
||||
(void)param_find("PWM_AUX_MIN");
|
||||
(void)param_find("PWM_AUX_MAX");
|
||||
(void)param_find("PWM_AUX_DISARMED");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
|
||||
@@ -59,6 +59,7 @@
|
||||
|
||||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/err.h"
|
||||
#include "systemlib/param/param.h"
|
||||
#include "drivers/drv_pwm_output.h"
|
||||
|
||||
static void usage(const char *reason);
|
||||
@@ -187,10 +188,35 @@ pwm_main(int argc, char *argv[])
|
||||
break;
|
||||
|
||||
case 'p':
|
||||
pwm_value = strtoul(optarg, &ep, 0);
|
||||
{
|
||||
/* check if this is a param name */
|
||||
if (strncmp("p:", optarg, 2) == 0) {
|
||||
|
||||
if (*ep != '\0') {
|
||||
usage("BAD PWM VAL");
|
||||
char buf[32];
|
||||
strncpy(buf, optarg + 2, 16);
|
||||
/* user wants to use a param name */
|
||||
param_t parm = param_find(buf);
|
||||
|
||||
if (parm != PARAM_INVALID) {
|
||||
int32_t pwm_parm;
|
||||
int gret = param_get(parm, &pwm_parm);
|
||||
|
||||
if (gret == 0) {
|
||||
pwm_value = pwm_parm;
|
||||
} else {
|
||||
usage("PARAM LOAD FAIL");
|
||||
}
|
||||
} else {
|
||||
usage("PARAM NAME NOT FOUND");
|
||||
}
|
||||
} else {
|
||||
|
||||
pwm_value = strtoul(optarg, &ep, 0);
|
||||
}
|
||||
|
||||
if (*ep != '\0') {
|
||||
usage("BAD PWM VAL");
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
Reference in New Issue
Block a user