mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
delete PWM_SERVO_SET, PWM_SERVO_SET_MODE, systemcmds/motor_ramp, and pwm_out test
This commit is contained in:
@@ -164,7 +164,6 @@ led_control,CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
mft,CONFIG_SYSTEMCMDS_MFT=y
|
||||
microbench,CONFIG_SYSTEMCMDS_MICROBENCH=y
|
||||
mixer,CONFIG_SYSTEMCMDS_MIXER=y
|
||||
motor_ramp,CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
motor_test,CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
mtd,CONFIG_SYSTEMCMDS_MTD=y
|
||||
netman,CONFIG_SYSTEMCMDS_NETMAN=y
|
||||
|
||||
@@ -85,7 +85,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -37,7 +37,6 @@ CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
|
||||
@@ -82,7 +82,6 @@ CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_NETMAN=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -61,7 +61,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
|
||||
@@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -86,7 +86,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -63,7 +63,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
|
||||
@@ -81,7 +81,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -91,7 +91,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -86,7 +86,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -81,7 +81,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -83,7 +83,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -82,7 +82,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -85,7 +85,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -85,7 +85,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -79,7 +79,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -83,7 +83,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -88,7 +88,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -89,7 +89,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -86,7 +86,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -91,7 +91,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -92,7 +92,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NETMAN=y
|
||||
|
||||
@@ -84,7 +84,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -60,7 +60,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
|
||||
@@ -50,7 +50,6 @@ CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_FAILURE=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
|
||||
@@ -58,7 +58,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_DYN=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_PWM=y
|
||||
|
||||
@@ -70,7 +70,6 @@ CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MIXER=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_RAMP=y
|
||||
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
|
||||
@@ -194,11 +194,6 @@ typedef uint16_t servo_position_t;
|
||||
/** force safety switch on (to enable use of safety switch) */
|
||||
#define PWM_SERVO_SET_FORCE_SAFETY_ON _PX4_IOC(_PWM_SERVO_BASE, 28)
|
||||
|
||||
/** set auxillary output mode */
|
||||
#define PWM_SERVO_ENTER_TEST_MODE 18
|
||||
#define PWM_SERVO_EXIT_TEST_MODE 19
|
||||
#define PWM_SERVO_SET_MODE _PX4_IOC(_PWM_SERVO_BASE, 34)
|
||||
|
||||
/*
|
||||
*
|
||||
*
|
||||
@@ -207,9 +202,6 @@ typedef uint16_t servo_position_t;
|
||||
*
|
||||
*/
|
||||
|
||||
/** set a single servo to a specific value */
|
||||
#define PWM_SERVO_SET(_servo) _PX4_IOC(_PWM_SERVO_BASE, 0x30 + _servo)
|
||||
|
||||
/** get a single specific servo value */
|
||||
#define PWM_SERVO_GET(_servo) _PX4_IOC(_PWM_SERVO_BASE, 0x50 + _servo)
|
||||
|
||||
|
||||
@@ -411,10 +411,6 @@ bool PWMOut::update_pwm_out_state(bool on)
|
||||
bool PWMOut::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
unsigned num_outputs, unsigned num_control_groups_updated)
|
||||
{
|
||||
if (_test_mode) {
|
||||
return false;
|
||||
}
|
||||
|
||||
/* output to the servos */
|
||||
if (_pwm_initialized) {
|
||||
for (size_t i = 0; i < num_outputs; i++) {
|
||||
@@ -855,47 +851,6 @@ int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
}
|
||||
break;
|
||||
|
||||
#if defined(DIRECT_PWM_OUTPUT_CHANNELS) && DIRECT_PWM_OUTPUT_CHANNELS >= 14
|
||||
|
||||
case PWM_SERVO_SET(13):
|
||||
case PWM_SERVO_SET(12):
|
||||
case PWM_SERVO_SET(11):
|
||||
case PWM_SERVO_SET(10):
|
||||
case PWM_SERVO_SET(9):
|
||||
case PWM_SERVO_SET(8):
|
||||
#endif
|
||||
#if defined(DIRECT_PWM_OUTPUT_CHANNELS) && DIRECT_PWM_OUTPUT_CHANNELS >= 8
|
||||
case PWM_SERVO_SET(7):
|
||||
case PWM_SERVO_SET(6):
|
||||
#endif
|
||||
#if defined(DIRECT_PWM_OUTPUT_CHANNELS) && DIRECT_PWM_OUTPUT_CHANNELS >= 6
|
||||
case PWM_SERVO_SET(5):
|
||||
#endif
|
||||
#if defined(DIRECT_PWM_OUTPUT_CHANNELS) && DIRECT_PWM_OUTPUT_CHANNELS >= 5
|
||||
case PWM_SERVO_SET(4):
|
||||
#endif
|
||||
case PWM_SERVO_SET(3):
|
||||
case PWM_SERVO_SET(2):
|
||||
case PWM_SERVO_SET(1):
|
||||
case PWM_SERVO_SET(0):
|
||||
if (cmd - PWM_SERVO_SET(0) >= (int)_num_outputs) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
if (arg <= 2100) {
|
||||
unsigned channel = cmd - PWM_SERVO_SET(0) + _output_base;
|
||||
|
||||
if (_pwm_mask & (1 << channel)) {
|
||||
up_pwm_servo_set(channel, arg);
|
||||
}
|
||||
|
||||
} else {
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
#if defined(DIRECT_PWM_OUTPUT_CHANNELS) && DIRECT_PWM_OUTPUT_CHANNELS >= 14
|
||||
|
||||
case PWM_SERVO_GET(13):
|
||||
@@ -956,23 +911,6 @@ int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
*(unsigned *)arg = _num_outputs;
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET_MODE: {
|
||||
switch (arg) {
|
||||
case PWM_SERVO_ENTER_TEST_MODE:
|
||||
_test_mode = true;
|
||||
break;
|
||||
|
||||
case PWM_SERVO_EXIT_TEST_MODE:
|
||||
_test_mode = false;
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case MIXERIOCRESET:
|
||||
_mixing_output.resetMixerThreadSafe();
|
||||
|
||||
@@ -997,165 +935,8 @@ int PWMOut::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
return ret;
|
||||
}
|
||||
|
||||
int PWMOut::test(const char *dev)
|
||||
{
|
||||
int fd;
|
||||
unsigned servo_count = 0;
|
||||
unsigned pwm_value = 1000;
|
||||
int direction = 1;
|
||||
int ret;
|
||||
int rv = -1;
|
||||
|
||||
fd = ::open(dev, O_RDWR);
|
||||
|
||||
if (fd < 0) {
|
||||
PX4_ERR("open fail");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_ENTER_TEST_MODE) < 0) {
|
||||
PX4_ERR("Failed to Enter pwm test mode");
|
||||
goto err_out_no_test;
|
||||
}
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_ARM, 0) < 0) {
|
||||
PX4_ERR("servo arm failed");
|
||||
goto err_out;
|
||||
}
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count) != 0) {
|
||||
PX4_ERR("Unable to get servo count");
|
||||
goto err_out;
|
||||
}
|
||||
|
||||
PX4_INFO("Testing %u servos", servo_count);
|
||||
|
||||
struct pollfd fds;
|
||||
|
||||
fds.fd = 0; /* stdin */
|
||||
|
||||
fds.events = POLLIN;
|
||||
|
||||
PX4_INFO("Press CTRL-C or 'c' to abort.");
|
||||
|
||||
for (;;) {
|
||||
/* sweep all servos between 1000..2000 */
|
||||
servo_position_t servos[servo_count];
|
||||
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
servos[i] = pwm_value;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
if (::ioctl(fd, PWM_SERVO_SET(i), servos[i]) < 0) {
|
||||
PX4_ERR("servo %u set failed", i);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
|
||||
if (direction > 0) {
|
||||
if (pwm_value < 2000) {
|
||||
pwm_value++;
|
||||
|
||||
} else {
|
||||
direction = -1;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (pwm_value > 1000) {
|
||||
pwm_value--;
|
||||
|
||||
} else {
|
||||
direction = 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* readback servo values */
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
servo_position_t value;
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&value)) {
|
||||
PX4_ERR("error reading PWM servo %u", i);
|
||||
goto err_out;
|
||||
}
|
||||
|
||||
if (value != servos[i]) {
|
||||
PX4_ERR("servo %u readback error, got %" PRIu16 " expected %" PRIu16, i, value, servos[i]);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check if user wants to quit */
|
||||
char c;
|
||||
ret = ::poll(&fds, 1, 0);
|
||||
|
||||
if (ret > 0) {
|
||||
|
||||
::read(0, &c, 1);
|
||||
|
||||
if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
PX4_INFO("User abort");
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rv = 0;
|
||||
|
||||
err_out:
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_EXIT_TEST_MODE) < 0) {
|
||||
PX4_ERR("Failed to Exit pwm test mode");
|
||||
}
|
||||
|
||||
err_out_no_test:
|
||||
::close(fd);
|
||||
return rv;
|
||||
}
|
||||
|
||||
int PWMOut::custom_command(int argc, char *argv[])
|
||||
{
|
||||
|
||||
int ch = 0;
|
||||
int myoptind = 0;
|
||||
const char *myoptarg = nullptr;
|
||||
const char *dev = PX4FMU_DEVICE_PATH;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'd':
|
||||
if (nullptr == strstr(myoptarg, "/dev/")) {
|
||||
PX4_WARN("device %s not valid", myoptarg);
|
||||
print_usage(nullptr);
|
||||
return 1;
|
||||
}
|
||||
|
||||
dev = myoptarg;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (myoptind >= argc) {
|
||||
print_usage(nullptr);
|
||||
return 1;
|
||||
}
|
||||
|
||||
const char *verb = argv[myoptind];
|
||||
|
||||
/* start pwm_out if not running */
|
||||
if (!is_running()) {
|
||||
|
||||
int ret = PWMOut::task_spawn(argc, argv);
|
||||
|
||||
if (ret) {
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "test")) {
|
||||
return test(dev);
|
||||
}
|
||||
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
@@ -1225,7 +1006,6 @@ By default the module runs on a work queue with a callback on the uORB actuator_
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("pwm_out", "driver");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Test outputs");
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
|
||||
return 0;
|
||||
|
||||
@@ -147,7 +147,6 @@ private:
|
||||
bool _pwm_on{false};
|
||||
uint32_t _pwm_mask{0};
|
||||
bool _pwm_initialized{false};
|
||||
bool _test_mode{false};
|
||||
|
||||
unsigned _num_disarmed_set{0};
|
||||
|
||||
|
||||
@@ -429,7 +429,7 @@ bool PX4IO::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
{
|
||||
SmartLock lock_guard(_lock);
|
||||
|
||||
if (!_test_fmu_fail && !_in_test_mode) {
|
||||
if (!_test_fmu_fail) {
|
||||
/* output to the servos */
|
||||
io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, outputs, num_outputs);
|
||||
}
|
||||
@@ -1755,32 +1755,6 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
||||
ret = dsm_bind_ioctl(arg);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(PWM_OUTPUT_MAX_CHANNELS - 1): {
|
||||
|
||||
/* TODO: we could go lower for e.g. TurboPWM */
|
||||
unsigned channel = cmd - PWM_SERVO_SET(0);
|
||||
|
||||
/* PWM needs to be either 0 or in the valid range. */
|
||||
if ((arg != 0) && ((channel >= _max_actuators) ||
|
||||
(arg < PWM_LOWEST_MIN) ||
|
||||
(arg > PWM_HIGHEST_MAX))) {
|
||||
ret = -EINVAL;
|
||||
|
||||
} else {
|
||||
if (!_test_fmu_fail && _in_test_mode) {
|
||||
/* send a direct PWM value */
|
||||
ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, channel, arg);
|
||||
|
||||
} else {
|
||||
/* Just silently accept the ioctl without doing anything
|
||||
* in test mode. */
|
||||
ret = OK;
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(PWM_OUTPUT_MAX_CHANNELS - 1): {
|
||||
|
||||
unsigned channel = cmd - PWM_SERVO_GET(0);
|
||||
@@ -1816,22 +1790,6 @@ int PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
|
||||
break;
|
||||
}
|
||||
|
||||
case PWM_SERVO_SET_MODE: {
|
||||
// reset all channels to disarmed when entering/leaving test mode, so that we don't
|
||||
// accidentially use values from previous tests
|
||||
pwm_output_values pwm_disarmed;
|
||||
|
||||
if (io_reg_get(PX4IO_PAGE_DISARMED_PWM, 0, pwm_disarmed.values, _max_actuators) == 0) {
|
||||
for (unsigned i = 0; i < _max_actuators; ++i) {
|
||||
io_reg_set(PX4IO_PAGE_DIRECT_PWM, i, pwm_disarmed.values[i]);
|
||||
}
|
||||
}
|
||||
|
||||
_in_test_mode = (arg == PWM_SERVO_ENTER_TEST_MODE);
|
||||
ret = (arg == PWM_SERVO_ENTER_TEST_MODE || PWM_SERVO_EXIT_TEST_MODE) ? 0 : -EINVAL;
|
||||
}
|
||||
break;
|
||||
|
||||
case MIXERIOCRESET:
|
||||
PX4_DEBUG("MIXERIOCRESET");
|
||||
_mixing_output.resetMixerThreadSafe();
|
||||
|
||||
@@ -1,40 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# 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 systemcmds__motor_ramp
|
||||
MAIN motor_ramp
|
||||
COMPILE_FLAGS
|
||||
-Wno-write-strings
|
||||
SRCS
|
||||
motor_ramp.cpp
|
||||
)
|
||||
@@ -1,5 +0,0 @@
|
||||
menuconfig SYSTEMCMDS_MOTOR_RAMP
|
||||
bool "motor_ramp"
|
||||
default n
|
||||
---help---
|
||||
Enable support for motor_ramp
|
||||
File diff suppressed because it is too large
Load Diff
+3
-238
@@ -123,15 +123,11 @@ $ pwm test -c 13 -p 1200
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("min", "Set Minimum PWM value");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("max", "Set Maximum PWM value");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test", "Set Output to a specific value until 'q' or 'c' or 'ctrl-c' pressed");
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("steps", "Run 5 steps from 0 to 100%");
|
||||
|
||||
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'min', 'max' and 'test' require a PWM value:");
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'min' and 'max' require a PWM value:");
|
||||
PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 4000, "PWM value (eg. 1100)", false);
|
||||
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'rate', 'oneshot', 'min', 'max', 'test' and 'steps' "
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The commands 'rate', 'oneshot', 'min', 'max' "
|
||||
"additionally require to specify the channels with one of the following commands:");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('c', nullptr, nullptr, "select channels in the form: 1234 (1 digit per channel, 1=first)",
|
||||
true);
|
||||
@@ -159,7 +155,7 @@ pwm_main(int argc, char *argv[])
|
||||
bool oneshot = false;
|
||||
int ch;
|
||||
int ret;
|
||||
int rv = 1;
|
||||
|
||||
char *ep;
|
||||
uint32_t set_mask = 0;
|
||||
unsigned group;
|
||||
@@ -497,237 +493,6 @@ pwm_main(int argc, char *argv[])
|
||||
|
||||
return 0;
|
||||
|
||||
} else if (!strcmp(command, "test")) {
|
||||
|
||||
if (set_mask == 0) {
|
||||
usage("no channels set");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (pwm_value == 0) {
|
||||
usage("no PWM provided");
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* get current servo values */
|
||||
struct pwm_output_values last_spos;
|
||||
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
|
||||
|
||||
ret = px4_ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&last_spos.values[i]);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_GET(%d)", i);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* perform PWM output */
|
||||
|
||||
/* Open console directly to grab CTRL-C signal */
|
||||
struct pollfd fds;
|
||||
fds.fd = 0; /* stdin */
|
||||
fds.events = POLLIN;
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_ENTER_TEST_MODE) < 0) {
|
||||
PX4_ERR("Failed to Enter pwm test mode");
|
||||
goto err_out_no_test;
|
||||
}
|
||||
|
||||
PX4_INFO("Press CTRL-C or 'c' to abort.");
|
||||
|
||||
while (1) {
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
if (set_mask & 1 << i) {
|
||||
ret = px4_ioctl(fd, PWM_SERVO_SET(i), pwm_value);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_SET(%d)", i);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* abort on user request */
|
||||
char c;
|
||||
ret = poll(&fds, 1, 0);
|
||||
|
||||
if (ret > 0) {
|
||||
|
||||
ret = read(0, &c, 1);
|
||||
|
||||
if (c == 0x03 || c == 0x63 || c == 'q') {
|
||||
/* reset output to the last value */
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
if (set_mask & 1 << i) {
|
||||
ret = px4_ioctl(fd, PWM_SERVO_SET(i), last_spos.values[i]);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_SET(%d)", i);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
PX4_INFO("User abort\n");
|
||||
rv = 0;
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
|
||||
/* Delay longer than the max Oneshot duration */
|
||||
|
||||
px4_usleep(2542);
|
||||
|
||||
#ifdef __PX4_NUTTX
|
||||
/* Trigger all timer's channels in Oneshot mode to fire
|
||||
* the oneshots with updated values.
|
||||
*/
|
||||
|
||||
up_pwm_update(0xff);
|
||||
#endif
|
||||
}
|
||||
rv = 0;
|
||||
err_out:
|
||||
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_EXIT_TEST_MODE) < 0) {
|
||||
rv = 1;
|
||||
PX4_ERR("Failed to Exit pwm test mode");
|
||||
}
|
||||
|
||||
err_out_no_test:
|
||||
return rv;
|
||||
|
||||
|
||||
} else if (!strcmp(command, "steps")) {
|
||||
|
||||
if (set_mask == 0) {
|
||||
usage("no channels set");
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* get current servo values */
|
||||
struct pwm_output_values last_spos;
|
||||
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
|
||||
ret = px4_ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&last_spos.values[i]);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_GET(%d)", i);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* perform PWM output */
|
||||
|
||||
/* Open console directly to grab CTRL-C signal */
|
||||
struct pollfd fds;
|
||||
fds.fd = 0; /* stdin */
|
||||
fds.events = POLLIN;
|
||||
|
||||
PX4_WARN("Running 5 steps. WARNING! Motors will be live in 5 seconds\nPress any key to abort now.");
|
||||
px4_sleep(5);
|
||||
|
||||
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_ENTER_TEST_MODE) < 0) {
|
||||
PX4_ERR("Failed to Enter pwm test mode");
|
||||
goto err_out_no_test;
|
||||
}
|
||||
|
||||
unsigned off = 900;
|
||||
unsigned idle = 1300;
|
||||
unsigned full = 2000;
|
||||
unsigned steps_timings_us[] = {2000, 5000, 20000, 50000};
|
||||
|
||||
unsigned phase = 0;
|
||||
unsigned phase_counter = 0;
|
||||
unsigned const phase_maxcount = 20;
|
||||
|
||||
for (unsigned steps_timing_index = 0;
|
||||
steps_timing_index < sizeof(steps_timings_us) / sizeof(steps_timings_us[0]);
|
||||
steps_timing_index++) {
|
||||
|
||||
PX4_INFO("Step input (0 to 100%%) over %u us ramp", steps_timings_us[steps_timing_index]);
|
||||
|
||||
while (1) {
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
if (set_mask & 1 << i) {
|
||||
|
||||
unsigned val;
|
||||
|
||||
if (phase == 0) {
|
||||
val = idle;
|
||||
|
||||
} else if (phase == 1) {
|
||||
/* ramp - depending how steep it is this ramp will look instantaneous on the output */
|
||||
val = idle + (full - idle) * ((float)phase_counter / phase_maxcount);
|
||||
|
||||
} else {
|
||||
val = off;
|
||||
}
|
||||
|
||||
ret = px4_ioctl(fd, PWM_SERVO_SET(i), val);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_SET(%d)", i);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* abort on user request */
|
||||
char c;
|
||||
ret = poll(&fds, 1, 0);
|
||||
|
||||
if (ret > 0) {
|
||||
|
||||
ret = read(0, &c, 1);
|
||||
|
||||
if (ret > 0) {
|
||||
/* reset output to the last value */
|
||||
for (unsigned i = 0; i < servo_count; i++) {
|
||||
if (set_mask & 1 << i) {
|
||||
ret = px4_ioctl(fd, PWM_SERVO_SET(i), last_spos.values[i]);
|
||||
|
||||
if (ret != OK) {
|
||||
PX4_ERR("PWM_SERVO_SET(%d)", i);
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
PX4_INFO("User abort\n");
|
||||
rv = 0;
|
||||
goto err_out;
|
||||
}
|
||||
}
|
||||
|
||||
if (phase == 1) {
|
||||
px4_usleep(steps_timings_us[steps_timing_index] / phase_maxcount);
|
||||
|
||||
} else if (phase == 0) {
|
||||
px4_usleep(50000);
|
||||
|
||||
} else if (phase == 2) {
|
||||
px4_usleep(50000);
|
||||
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
|
||||
phase_counter++;
|
||||
|
||||
if (phase_counter > phase_maxcount) {
|
||||
phase++;
|
||||
phase_counter = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
rv = 0;
|
||||
goto err_out;
|
||||
|
||||
|
||||
} else if (!strcmp(command, "status") || !strcmp(command, "info")) {
|
||||
|
||||
printf("device: %s\n", dev);
|
||||
|
||||
Reference in New Issue
Block a user