aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/10_dji_f33012
-rw-r--r--ROMFS/px4fmu_common/init.d/11_dji_f45013
-rw-r--r--ROMFS/px4fmu_common/init.d/15_tbs_discovery13
-rw-r--r--ROMFS/px4fmu_common/init.d/16_3dr_iris13
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x5502
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl10
-rw-r--r--src/drivers/drv_pwm_output.h64
-rw-r--r--src/drivers/hil/hil.cpp4
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp185
-rw-r--r--src/drivers/px4fmu/module.mk3
-rw-r--r--src/drivers/px4io/px4io.cpp208
-rw-r--r--src/modules/px4iofirmware/mixer.cpp139
-rw-r--r--src/modules/px4iofirmware/module.mk1
-rw-r--r--src/modules/px4iofirmware/protocol.h4
-rw-r--r--src/modules/px4iofirmware/px4io.c6
-rw-r--r--src/modules/px4iofirmware/px4io.h9
-rw-r--r--src/modules/px4iofirmware/registers.c67
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c117
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.h77
-rw-r--r--src/modules/uORB/topics/actuator_outputs.h2
-rw-r--r--src/systemcmds/pwm/pwm.c463
22 files changed, 946 insertions, 468 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10_dji_f330 b/ROMFS/px4fmu_common/init.d/10_dji_f330
index d21759507..e7a62a4b8 100644
--- a/ROMFS/px4fmu_common/init.d/10_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/10_dji_f330
@@ -61,9 +61,6 @@ then
sh /etc/init.d/rc.io
# Set PWM values for DJI ESCs
- px4io idle 900 900 900 900
- px4io min 1200 1200 1200 1200
- px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
@@ -81,7 +78,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/11_dji_f450 b/ROMFS/px4fmu_common/init.d/11_dji_f450
index 388f40a47..91847b06b 100644
--- a/ROMFS/px4fmu_common/init.d/11_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/11_dji_f450
@@ -44,10 +44,6 @@ then
usleep 5000
sh /etc/init.d/rc.io
- # Set PWM values for DJI ESCs
- px4io idle 900 900 900 900
- px4io min 1200 1200 1200 1200
- px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
@@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals (for DJI ESCs)
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
index cbfde6d3c..65be56df8 100644
--- a/ROMFS/px4fmu_common/init.d/15_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -44,10 +44,6 @@ then
usleep 5000
sh /etc/init.d/rc.io
- # Set PWM values for DJI ESCs
- px4io idle 900 900 900 900
- px4io min 1200 1200 1200 1200
- px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
@@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals (for DJI ESCs)
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/16_3dr_iris b/ROMFS/px4fmu_common/init.d/16_3dr_iris
index d47ecb393..3434735fd 100644
--- a/ROMFS/px4fmu_common/init.d/16_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/16_3dr_iris
@@ -44,10 +44,6 @@ then
usleep 5000
sh /etc/init.d/rc.io
- # Set PWM values for DJI ESCs
- px4io idle 900 900 900 900
- px4io min 1200 1200 1200 1200
- px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
@@ -65,7 +61,14 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -c 1234 -r 400
+
+#
+# Set disarmed, min and max PWM signals
+#
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
index ae41f2a01..eae37098b 100644
--- a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -53,7 +53,7 @@ mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
-pwm -u 400 -m 0xff
+pwm rate -c 1234 -r 400
#
# Start common for all multirotors apps
diff --git a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
index 51bc61c9e..a63d0e5f1 100644
--- a/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
+++ b/ROMFS/px4fmu_common/init.d/rc.custom_dji_f330_mkblctrl
@@ -83,10 +83,6 @@ then
usleep 5000
sh /etc/init.d/rc.io
- # Set PWM values for DJI ESCs
- px4io idle 900 900 900 900
- px4io min 1200 1200 1200 1200
- px4io max 1800 1800 1800 1800
else
fmu mode_pwm
# Start MAVLink (on UART1 / ttyS0)
@@ -107,9 +103,11 @@ else
fi
#
-# Set PWM output frequency
+# Set disarmed, min and max PWM signals
#
-#pwm -u 400 -m 0xff
+pwm disarmed -c 1234 -p 900
+pwm min -c 1234 -p 1200
+pwm max -c 1234 -p 1800
#
# Start common for all multirotors apps
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 94e923d71..3357e67a5 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -65,6 +65,26 @@ __BEGIN_DECLS
#define PWM_OUTPUT_MAX_CHANNELS 16
/**
+ * Minimum PWM in us
+ */
+#define PWM_MIN 900
+
+/**
+ * Highest PWM allowed as the minimum PWM
+ */
+#define PWM_HIGHEST_MIN 1300
+
+/**
+ * Maximum PWM in us
+ */
+#define PWM_MAX 2100
+
+/**
+ * Lowest PWM allowed as the maximum PWM
+ */
+#define PWM_LOWEST_MAX 1700
+
+/**
* Servo output signal type, value is actual servo output pulse
* width in microseconds.
*/
@@ -79,6 +99,7 @@ typedef uint16_t servo_position_t;
struct pwm_output_values {
/** desired pulse widths for each of the supported channels */
servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
+ unsigned channel_count;
};
/*
@@ -100,29 +121,56 @@ ORB_DECLARE(output_pwm);
/** disarm all servo outputs (stop generating pulses) */
#define PWM_SERVO_DISARM _IOC(_PWM_SERVO_BASE, 1)
+/** get default servo update rate */
+#define PWM_SERVO_GET_DEFAULT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+
/** set alternate servo update rate */
-#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 2)
+#define PWM_SERVO_SET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 3)
+
+/** get alternate servo update rate */
+#define PWM_SERVO_GET_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
/** get the number of servos in *(unsigned *)arg */
-#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 3)
+#define PWM_SERVO_GET_COUNT _IOC(_PWM_SERVO_BASE, 5)
/** selects servo update rates, one bit per servo. 0 = default (50Hz), 1 = alternate */
-#define PWM_SERVO_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4)
+#define PWM_SERVO_SET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 6)
+
+/** check the selected update rates */
+#define PWM_SERVO_GET_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 7)
/** set the 'ARM ok' bit, which activates the safety switch */
-#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 5)
+#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 8)
/** clear the 'ARM ok' bit, which deactivates the safety switch */
-#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 6)
+#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 9)
/** start DSM bind */
-#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7)
+#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 10)
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
-/** Power up DSM receiver */
-#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8)
+/** power up DSM receiver */
+#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
+
+/** set the PWM value when disarmed - should be no PWM (zero) by default */
+#define PWM_SERVO_SET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 12)
+
+/** get the PWM value when disarmed */
+#define PWM_SERVO_GET_DISARMED_PWM _IOC(_PWM_SERVO_BASE, 13)
+
+/** set the minimum PWM value the output will send */
+#define PWM_SERVO_SET_MIN_PWM _IOC(_PWM_SERVO_BASE, 14)
+
+/** get the minimum PWM value the output will send */
+#define PWM_SERVO_GET_MIN_PWM _IOC(_PWM_SERVO_BASE, 15)
+
+/** set the maximum PWM value the output will send */
+#define PWM_SERVO_SET_MAX_PWM _IOC(_PWM_SERVO_BASE, 16)
+
+/** get the maximum PWM value the output will send */
+#define PWM_SERVO_GET_MAX_PWM _IOC(_PWM_SERVO_BASE, 17)
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 3e30e3292..c1d73dd87 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -404,7 +404,7 @@ HIL::task_main()
for (unsigned i = 0; i < num_outputs; i++) {
/* last resort: catch NaN, INF and out-of-band errors */
- if (i < (unsigned)outputs.noutputs &&
+ if (i < outputs.noutputs &&
isfinite(outputs.output[i]) &&
outputs.output[i] >= -1.0f &&
outputs.output[i] <= 1.0f) {
@@ -517,7 +517,7 @@ HIL::pwm_ioctl(file *filp, int cmd, unsigned long arg)
g_hil->set_pwm_rate(arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
// HIL always outputs at the alternate (usually faster) rate
break;
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index d0de26a1a..b93f38cf6 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -1071,7 +1071,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
ret = OK;
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
ret = OK;
break;
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index b1dd55dd7..8e9e8103f 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -59,11 +59,12 @@
#include <drivers/drv_gpio.h>
#include <drivers/drv_hrt.h>
-# include <board_config.h>
+#include <board_config.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
#include <systemlib/mixer/mixer.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
#include <drivers/drv_mixer.h>
#include <drivers/drv_rc_input.h>
@@ -72,7 +73,7 @@
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
-#include <systemlib/err.h>
+
#ifdef HRT_PPM_CHANNEL
# include <systemlib/ppm_decode.h>
#endif
@@ -100,7 +101,7 @@ public:
int set_pwm_alt_channels(uint32_t channels);
private:
- static const unsigned _max_actuators = 4;
+ static const unsigned _max_actuators = 6;
Mode _mode;
unsigned _pwm_default_rate;
@@ -117,11 +118,18 @@ private:
volatile bool _task_should_exit;
bool _armed;
+ bool _pwm_on;
MixerGroup *_mixers;
actuator_controls_s _controls;
+ pwm_limit_t _pwm_limit;
+ uint16_t _disarmed_pwm[_max_actuators];
+ uint16_t _min_pwm[_max_actuators];
+ uint16_t _max_pwm[_max_actuators];
+ unsigned _num_disarmed_set;
+
static void task_main_trampoline(int argc, char *argv[]);
void task_main() __attribute__((noreturn));
@@ -203,7 +211,12 @@ PX4FMU::PX4FMU() :
_primary_pwm_device(false),
_task_should_exit(false),
_armed(false),
- _mixers(nullptr)
+ _pwm_on(false),
+ _mixers(nullptr),
+ _disarmed_pwm({0}),
+ _min_pwm({PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN}),
+ _max_pwm({PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX}),
+ _num_disarmed_set(0)
{
_debug_enabled = true;
}
@@ -457,6 +470,9 @@ PX4FMU::task_main()
rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM;
#endif
+ /* initialize PWM limit lib */
+ pwm_limit_init(&_pwm_limit);
+
log("starting");
/* loop until killed */
@@ -530,32 +546,35 @@ PX4FMU::task_main()
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
outputs.timestamp = hrt_absolute_time();
- // XXX output actual limited values
- memcpy(&controls_effective, &_controls, sizeof(controls_effective));
-
- orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective);
-
/* iterate actuators */
for (unsigned i = 0; i < num_outputs; i++) {
-
/* last resort: catch NaN, INF and out-of-band errors */
- if (i < outputs.noutputs &&
- isfinite(outputs.output[i]) &&
- outputs.output[i] >= -1.0f &&
- outputs.output[i] <= 1.0f) {
- /* scale for PWM output 900 - 2100us */
- outputs.output[i] = 1500 + (600 * outputs.output[i]);
- } else {
+ if (i >= outputs.noutputs ||
+ !isfinite(outputs.output[i]) ||
+ outputs.output[i] < -1.0f ||
+ outputs.output[i] > 1.0f) {
/*
* Value is NaN, INF or out of band - set to the minimum value.
* This will be clearly visible on the servo status and will limit the risk of accidentally
* spinning motors. It would be deadly in flight.
*/
- outputs.output[i] = 900;
+ outputs.output[i] = -1.0f;
}
+ }
+
+ uint16_t pwm_limited[num_outputs];
+
+ pwm_limit_calc(_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
+
+ /* output actual limited values */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ controls_effective.control_effective[i] = (float)pwm_limited[i];
+ }
+ orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective);
- /* output to the servo */
- up_pwm_servo_set(i, outputs.output[i]);
+ /* output to the servos */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ up_pwm_servo_set(i, pwm_limited[i]);
}
/* and publish for anyone that cares to see */
@@ -570,11 +589,16 @@ PX4FMU::task_main()
/* get new value */
orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
- /* update PWM servo armed status if armed and not locked down */
+ /* update the armed status and check that we're not locked down */
bool set_armed = aa.armed && !aa.lockdown;
- if (set_armed != _armed) {
+ if (_armed != set_armed)
_armed = set_armed;
- up_pwm_servo_arm(set_armed);
+
+ /* update PWM status if armed or if disarmed PWM values are set */
+ bool pwm_on = (aa.armed || _num_disarmed_set > 0);
+ if (_pwm_on != pwm_on) {
+ _pwm_on = pwm_on;
+ up_pwm_servo_arm(pwm_on);
}
}
@@ -685,14 +709,125 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
up_pwm_servo_arm(false);
break;
+ case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_default_rate;
+ break;
+
case PWM_SERVO_SET_UPDATE_RATE:
ret = set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE:
+ case PWM_SERVO_GET_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_alt_rate;
+ break;
+
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE:
ret = set_pwm_rate(arg, _pwm_default_rate, _pwm_alt_rate);
break;
+ case PWM_SERVO_GET_SELECT_UPDATE_RATE:
+ *(uint32_t *)arg = _pwm_alt_rate_channels;
+ break;
+
+ case PWM_SERVO_SET_DISARMED_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values*)arg;
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] > PWM_MAX) {
+ _disarmed_pwm[i] = PWM_MAX;
+ } else if (pwm->values[i] < PWM_MIN) {
+ _disarmed_pwm[i] = PWM_MIN;
+ } else {
+ _disarmed_pwm[i] = pwm->values[i];
+ }
+ }
+
+ /*
+ * update the counter
+ * this is needed to decide if disarmed PWM output should be turned on or not
+ */
+ _num_disarmed_set = 0;
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ if (_disarmed_pwm[i] > 0)
+ _num_disarmed_set++;
+ }
+ break;
+ }
+ case PWM_SERVO_GET_DISARMED_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values*)arg;
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _disarmed_pwm[i];
+ }
+ pwm->channel_count = _max_actuators;
+ break;
+ }
+
+ case PWM_SERVO_SET_MIN_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] > PWM_HIGHEST_MIN) {
+ _min_pwm[i] = PWM_HIGHEST_MIN;
+ } else if (pwm->values[i] < PWM_MIN) {
+ _min_pwm[i] = PWM_MIN;
+ } else {
+ _min_pwm[i] = pwm->values[i];
+ }
+ }
+ break;
+ }
+ case PWM_SERVO_GET_MIN_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values*)arg;
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _min_pwm[i];
+ }
+ pwm->channel_count = _max_actuators;
+ arg = (unsigned long)&pwm;
+ break;
+ }
+
+ case PWM_SERVO_SET_MAX_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ /* discard if too many values are sent */
+ if (pwm->channel_count > _max_actuators) {
+ ret = -EINVAL;
+ break;
+ }
+ for (unsigned i = 0; i < pwm->channel_count; i++) {
+ if (pwm->values[i] == 0) {
+ /* ignore 0 */
+ } else if (pwm->values[i] < PWM_LOWEST_MAX) {
+ _max_pwm[i] = PWM_LOWEST_MAX;
+ } else if (pwm->values[i] > PWM_MAX) {
+ _max_pwm[i] = PWM_MAX;
+ } else {
+ _max_pwm[i] = pwm->values[i];
+ }
+ }
+ break;
+ }
+ case PWM_SERVO_GET_MAX_PWM: {
+ struct pwm_output_values *pwm = (struct pwm_output_values*)arg;
+ for (unsigned i = 0; i < _max_actuators; i++) {
+ pwm->values[i] = _max_pwm[i];
+ }
+ pwm->channel_count = _max_actuators;
+ arg = (unsigned long)&pwm;
+ break;
+ }
+
case PWM_SERVO_SET(5):
case PWM_SERVO_SET(4):
if (_mode < MODE_6PWM) {
@@ -1136,7 +1271,7 @@ test(void)
}
} else {
// and use write interface for the other direction
- int ret = write(fd, servos, sizeof(servos));
+ ret = write(fd, servos, sizeof(servos));
if (ret != (int)sizeof(servos))
err(1, "error writing PWM servo data, wrote %u got %d", sizeof(servos), ret);
}
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index 05bc7a5b3..d918abd57 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -3,4 +3,5 @@
#
MODULE_COMMAND = fmu
-SRCS = fmu.cpp
+SRCS = fmu.cpp \
+ ../../modules/systemlib/pwm_limit/pwm_limit.c
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index f6d4f1ed4..d709f1cc8 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -181,21 +181,6 @@ public:
int set_failsafe_values(const uint16_t *vals, unsigned len);
/**
- * Set the minimum PWM signals when armed
- */
- int set_min_values(const uint16_t *vals, unsigned len);
-
- /**
- * Set the maximum PWM signal when armed
- */
- int set_max_values(const uint16_t *vals, unsigned len);
-
- /**
- * Set an idle PWM signal that is active right after startup, even when SAFETY_SAFE
- */
- int set_idle_values(const uint16_t *vals, unsigned len);
-
- /**
* Disable RC input handling
*/
int disable_rc_handling();
@@ -409,6 +394,21 @@ private:
int mixer_send(const char *buf, unsigned buflen, unsigned retries=3);
/**
+ * Set the minimum PWM signals when armed
+ */
+ int set_min_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set the maximum PWM signal when armed
+ */
+ int set_max_values(const uint16_t *vals, unsigned len);
+
+ /**
+ * Set an idle PWM signal that is active right after startup, even when SAFETY_SAFE
+ */
+ int set_idle_values(const uint16_t *vals, unsigned len);
+
+ /**
* Handle a status update from IO.
*
* Publish IO status information if necessary.
@@ -986,10 +986,8 @@ PX4IO::set_idle_values(const uint16_t *vals, unsigned len)
/* fail with error */
return E2BIG;
- printf("Sending IDLE values\n");
-
/* copy values to registers in IO */
- return io_reg_set(PX4IO_PAGE_IDLE_PWM, 0, vals, len);
+ return io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, vals, len);
}
@@ -1807,7 +1805,7 @@ PX4IO::print_status()
printf(" %u", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
printf("\nidle values");
for (unsigned i = 0; i < _max_actuators; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_IDLE_PWM, i));
+ printf(" %u", io_reg_get(PX4IO_PAGE_DISARMED_PWM, i));
printf("\n");
}
@@ -1839,12 +1837,22 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FMU_ARMED, 0);
break;
+ case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
+ /* get the default update rate */
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE);
+ break;
+
case PWM_SERVO_SET_UPDATE_RATE:
/* set the requested alternate rate */
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE, arg);
break;
- case PWM_SERVO_SELECT_UPDATE_RATE: {
+ case PWM_SERVO_GET_UPDATE_RATE:
+ /* get the alternative update rate */
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE);
+ break;
+
+ case PWM_SERVO_SET_SELECT_UPDATE_RATE: {
/* blindly clear the PWM update alarm - might be set for some other reason */
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
@@ -1861,6 +1869,53 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
break;
}
+ case PWM_SERVO_GET_SELECT_UPDATE_RATE:
+
+ *(unsigned *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES);
+ break;
+
+ case PWM_SERVO_SET_DISARMED_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ set_idle_values(pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_DISARMED_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_DISARMED_PWM, 0, (uint16_t*)arg, sizeof(struct pwm_output_values)/sizeof(uint16_t));
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
+ case PWM_SERVO_SET_MIN_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ set_min_values(pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_MIN_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_CONTROL_MIN_PWM, 0, (uint16_t*)arg, sizeof(struct pwm_output_values)/sizeof(uint16_t));
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
+ case PWM_SERVO_SET_MAX_PWM: {
+ struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
+ set_max_values(pwm->values, pwm->channel_count);
+ break;
+ }
+
+ case PWM_SERVO_GET_MAX_PWM:
+
+ ret = io_reg_get(PX4IO_PAGE_CONTROL_MAX_PWM, 0, (uint16_t*)arg, sizeof(struct pwm_output_values)/sizeof(uint16_t));
+ if (ret != OK) {
+ ret = -EIO;
+ }
+ break;
+
case PWM_SERVO_GET_COUNT:
*(unsigned *)arg = _max_actuators;
break;
@@ -1884,7 +1939,7 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
/* TODO: we could go lower for e.g. TurboPWM */
unsigned channel = cmd - PWM_SERVO_SET(0);
- if ((channel >= _max_actuators) || (arg < 900) || (arg > 2100)) {
+ if ((channel >= _max_actuators) || (arg < PWM_MIN) || (arg > PWM_MAX)) {
ret = -EINVAL;
} else {
/* send a direct PWM value */
@@ -2475,10 +2530,10 @@ px4io_main(int argc, char *argv[])
for (unsigned i = 0; i < sizeof(failsafe) / sizeof(failsafe[0]); i++) {
/* set channel to commandline argument or to 900 for non-provided channels */
- if (argc > i + 2) {
+ if ((unsigned)argc > i + 2) {
failsafe[i] = atoi(argv[i+2]);
- if (failsafe[i] < 800 || failsafe[i] > 2200) {
- errx(1, "value out of range of 800 < value < 2200. Aborting.");
+ if (failsafe[i] < PWM_MIN || failsafe[i] > PWM_MAX) {
+ errx(1, "value out of range of %d < value < %d. Aborting.", PWM_MIN, PWM_MAX);
}
} else {
/* a zero value will result in stopping to output any pulse */
@@ -2493,110 +2548,7 @@ px4io_main(int argc, char *argv[])
exit(0);
}
- if (!strcmp(argv[1], "min")) {
-
- if (argc < 3) {
- errx(1, "min command needs at least one channel value (PWM)");
- }
-
- if (g_dev != nullptr) {
-
- /* set values for first 8 channels, fill unassigned channels with 900. */
- uint16_t min[8];
-
- for (unsigned i = 0; i < sizeof(min) / sizeof(min[0]); i++)
- {
- /* set channel to commanline argument or to 900 for non-provided channels */
- if (argc > i + 2) {
- min[i] = atoi(argv[i+2]);
- if (min[i] < 900 || min[i] > 1200) {
- errx(1, "value out of range of 900 < value < 1200. Aborting.");
- }
- } else {
- /* a zero value will the default */
- min[i] = 0;
- }
- }
-
- int ret = g_dev->set_min_values(min, sizeof(min) / sizeof(min[0]));
-
- if (ret != OK)
- errx(ret, "failed setting min values");
- } else {
- errx(1, "not loaded");
- }
- exit(0);
- }
-
- if (!strcmp(argv[1], "max")) {
-
- if (argc < 3) {
- errx(1, "max command needs at least one channel value (PWM)");
- }
-
- if (g_dev != nullptr) {
-
- /* set values for first 8 channels, fill unassigned channels with 2100. */
- uint16_t max[8];
-
- for (unsigned i = 0; i < sizeof(max) / sizeof(max[0]); i++)
- {
- /* set channel to commanline argument or to 2100 for non-provided channels */
- if (argc > i + 2) {
- max[i] = atoi(argv[i+2]);
- if (max[i] < 1800 || max[i] > 2100) {
- errx(1, "value out of range of 1800 < value < 2100. Aborting.");
- }
- } else {
- /* a zero value will the default */
- max[i] = 0;
- }
- }
-
- int ret = g_dev->set_max_values(max, sizeof(max) / sizeof(max[0]));
-
- if (ret != OK)
- errx(ret, "failed setting max values");
- } else {
- errx(1, "not loaded");
- }
- exit(0);
- }
-
- if (!strcmp(argv[1], "idle")) {
- if (argc < 3) {
- errx(1, "max command needs at least one channel value (PWM)");
- }
-
- if (g_dev != nullptr) {
-
- /* set values for first 8 channels, fill unassigned channels with 0. */
- uint16_t idle[8];
-
- for (unsigned i = 0; i < sizeof(idle) / sizeof(idle[0]); i++)
- {
- /* set channel to commanline argument or to 0 for non-provided channels */
- if (argc > i + 2) {
- idle[i] = atoi(argv[i+2]);
- if (idle[i] < 900 || idle[i] > 2100) {
- errx(1, "value out of range of 900 < value < 2100. Aborting.");
- }
- } else {
- /* a zero value will the default */
- idle[i] = 0;
- }
- }
-
- int ret = g_dev->set_idle_values(idle, sizeof(idle) / sizeof(idle[0]));
-
- if (ret != OK)
- errx(ret, "failed setting idle values");
- } else {
- errx(1, "not loaded");
- }
- exit(0);
- }
if (!strcmp(argv[1], "recovery")) {
@@ -2664,5 +2616,5 @@ px4io_main(int argc, char *argv[])
bind(argc, argv);
out:
- errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug',\n 'recovery', 'limit', 'current', 'failsafe', 'min, 'max',\n 'idle', 'bind' or 'update'");
+ errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug',\n 'recovery', 'limit', 'current', 'failsafe', 'bind' or 'update'");
}
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 30aff7d20..05897b4ce 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -47,6 +47,7 @@
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
#include <systemlib/mixer/mixer.h>
extern "C" {
@@ -59,12 +60,6 @@ extern "C" {
*/
#define FMU_INPUT_DROP_LIMIT_US 200000
-/*
- * Time that the ESCs need to initialize
- */
- #define ESC_INIT_TIME_US 1000000
- #define ESC_RAMP_TIME_US 2000000
-
/* XXX need to move the RC_CHANNEL_FUNCTION out of rc_channels.h and into systemlib */
#define ROLL 0
#define PITCH 1
@@ -76,15 +71,6 @@ extern "C" {
static bool mixer_servos_armed = false;
static bool should_arm = false;
static bool should_always_enable_pwm = false;
-static uint64_t esc_init_time;
-
-enum esc_state_e {
- ESC_OFF,
- ESC_INIT,
- ESC_RAMP,
- ESC_ON
-};
-static esc_state_e esc_state;
/* selected control values and count for mixing */
enum mixer_source {
@@ -166,6 +152,30 @@ mixer_tick(void)
}
/*
+ * Decide whether the servos should be armed right now.
+ *
+ * We must be armed, and we must have a PWM source; either raw from
+ * FMU or from the mixer.
+ *
+ * XXX correct behaviour for failsafe may require an additional case
+ * here.
+ */
+ should_arm = (
+ /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
+ /* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
+ /* and FMU is armed */ && (
+ ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
+ /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
+ /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
+ /* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
+ )
+ );
+
+ should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
+ && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
+
+ /*
* Run the mixers.
*/
if (source == MIX_FAILSAFE) {
@@ -184,107 +194,15 @@ mixer_tick(void)
float outputs[PX4IO_SERVO_COUNT];
unsigned mixed;
- uint16_t ramp_promille;
-
- /* update esc init state, but only if we are truely armed and not just PWM enabled */
- if (mixer_servos_armed && should_arm) {
-
- switch (esc_state) {
-
- /* after arming, some ESCs need an initalization period, count the time from here */
- case ESC_OFF:
- esc_init_time = hrt_absolute_time();
- esc_state = ESC_INIT;
- break;
-
- /* after waiting long enough for the ESC initialization, we can start with the ramp to start the ESCs */
- case ESC_INIT:
- if (hrt_elapsed_time(&esc_init_time) > ESC_INIT_TIME_US) {
- esc_state = ESC_RAMP;
- }
- break;
-
- /* then ramp until the min speed is reached */
- case ESC_RAMP:
- if (hrt_elapsed_time(&esc_init_time) > (ESC_INIT_TIME_US + ESC_RAMP_TIME_US)) {
- esc_state = ESC_ON;
- }
- break;
-
- case ESC_ON:
- default:
-
- break;
- }
- } else {
- esc_state = ESC_OFF;
- }
-
- /* do the calculations during the ramp for all at once */
- if (esc_state == ESC_RAMP) {
- ramp_promille = (1000*(hrt_elapsed_time(&esc_init_time)-ESC_INIT_TIME_US))/ESC_RAMP_TIME_US;
- }
-
-
/* mix */
mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
- /* scale to PWM and update the servo outputs as required */
- for (unsigned i = 0; i < mixed; i++) {
-
- /* save actuator values for FMU readback */
- r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
-
- switch (esc_state) {
- case ESC_INIT:
- r_page_servos[i] = (outputs[i] * 600 + 1500);
- break;
-
- case ESC_RAMP:
- r_page_servos[i] = (outputs[i]
- * (ramp_promille*r_page_servo_control_max[i] + (1000-ramp_promille)*2100 - ramp_promille*r_page_servo_control_min[i] - (1000-ramp_promille)*900)/2/1000
- + (ramp_promille*r_page_servo_control_max[i] + (1000-ramp_promille)*2100 + ramp_promille*r_page_servo_control_min[i] + (1000-ramp_promille)*900)/2/1000);
- break;
-
- case ESC_ON:
- r_page_servos[i] = (outputs[i]
- * (r_page_servo_control_max[i] - r_page_servo_control_min[i])/2
- + (r_page_servo_control_max[i] + r_page_servo_control_min[i])/2);
- break;
+ pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
- case ESC_OFF:
- default:
- break;
- }
- }
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
r_page_servos[i] = 0;
}
- /*
- * Decide whether the servos should be armed right now.
- *
- * We must be armed, and we must have a PWM source; either raw from
- * FMU or from the mixer.
- *
- * XXX correct behaviour for failsafe may require an additional case
- * here.
- */
- should_arm = (
- /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
- /* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
- /* and FMU is armed */ && (
- ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)
- /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) )
- /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)
- /* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
- )
- );
-
- should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE)
- && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
- && (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
-
if ((should_arm || should_always_enable_pwm) && !mixer_servos_armed) {
/* need to arm, but not armed */
up_pwm_servo_arm(true);
@@ -298,7 +216,6 @@ mixer_tick(void)
mixer_servos_armed = false;
r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED);
isr_debug(5, "> PWM disabled");
-
}
if (mixer_servos_armed && should_arm) {
@@ -307,9 +224,9 @@ mixer_tick(void)
up_pwm_servo_set(i, r_page_servos[i]);
} else if (mixer_servos_armed && should_always_enable_pwm) {
- /* set the idle servo outputs. */
+ /* set the disarmed servo outputs. */
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
- up_pwm_servo_set(i, r_page_servo_idle[i]);
+ up_pwm_servo_set(i, r_page_servo_disarmed[i]);
}
}
diff --git a/src/modules/px4iofirmware/module.mk b/src/modules/px4iofirmware/module.mk
index 59f470a94..01869569f 100644
--- a/src/modules/px4iofirmware/module.mk
+++ b/src/modules/px4iofirmware/module.mk
@@ -14,6 +14,7 @@ SRCS = adc.c \
../systemlib/mixer/mixer_group.cpp \
../systemlib/mixer/mixer_multirotor.cpp \
../systemlib/mixer/mixer_simple.cpp \
+ ../systemlib/pwm_limit/pwm_limit.c
ifeq ($(BOARD),px4io-v1)
SRCS += i2c.c
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 0e2cd1689..5e5396782 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -220,8 +220,8 @@ enum { /* DSM bind states */
/* PWM maximum values for certain ESCs */
#define PX4IO_PAGE_CONTROL_MAX_PWM 107 /* 0..CONFIG_ACTUATOR_COUNT-1 */
-/* PWM idle values that are active, even when SAFETY_SAFE */
-#define PX4IO_PAGE_IDLE_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
+/* PWM disarmed values that are active, even when SAFETY_SAFE */
+#define PX4IO_PAGE_DISARMED_PWM 108 /* 0..CONFIG_ACTUATOR_COUNT-1 */
/**
* As-needed mixer data upload.
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index e70b3fe88..71d649029 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -50,6 +50,7 @@
#include <drivers/drv_hrt.h>
#include <systemlib/perf_counter.h>
+#include <systemlib/pwm_limit/pwm_limit.h>
#include <stm32_uart.h>
@@ -64,6 +65,8 @@ struct sys_state_s system_state;
static struct hrt_call serial_dma_call;
+pwm_limit_t pwm_limit;
+
/*
* a set of debug buffers to allow us to send debug information from ISRs
*/
@@ -174,6 +177,9 @@ user_start(int argc, char *argv[])
struct mallinfo minfo = mallinfo();
lowsyslog("MEM: free %u, largest %u\n", minfo.mxordblk, minfo.fordblks);
+ /* initialize PWM limit lib */
+ pwm_limit_init(&pwm_limit);
+
#if 0
/* not enough memory, lock down */
if (minfo.mxordblk < 500) {
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 66c4ca906..4fea0288c 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -46,6 +46,8 @@
#include "protocol.h"
+#include <systemlib/pwm_limit/pwm_limit.h>
+
/*
* Constants and limits.
*/
@@ -80,7 +82,7 @@ extern uint16_t r_page_rc_input_config[]; /* PX4IO_PAGE_RC_INPUT_CONFIG */
extern uint16_t r_page_servo_failsafe[]; /* PX4IO_PAGE_FAILSAFE_PWM */
extern uint16_t r_page_servo_control_min[]; /* PX4IO_PAGE_CONTROL_MIN_PWM */
extern uint16_t r_page_servo_control_max[]; /* PX4IO_PAGE_CONTROL_MAX_PWM */
-extern uint16_t r_page_servo_idle[]; /* PX4IO_PAGE_IDLE_PWM */
+extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
/*
* Register aliases.
@@ -123,6 +125,11 @@ struct sys_state_s {
extern struct sys_state_s system_state;
/*
+ * PWM limit structure
+ */
+extern pwm_limit_t pwm_limit;
+
+/*
* GPIO handling.
*/
#define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED1, !(_s))
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 9d9ef7c6d..a338afe16 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -207,7 +207,7 @@ uint16_t r_page_servo_failsafe[PX4IO_SERVO_COUNT] = { 0 };
* minimum PWM values when armed
*
*/
-uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 };
+uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN };
/**
* PAGE 107
@@ -215,15 +215,15 @@ uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { 900, 900, 900, 900, 90
* maximum PWM values when armed
*
*/
-uint16_t r_page_servo_control_max[PX4IO_SERVO_COUNT] = { 2100, 2100, 2100, 2100, 2100, 2100, 2100, 2100 };
+uint16_t r_page_servo_control_max[PX4IO_SERVO_COUNT] = { PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX };
/**
* PAGE 108
*
- * idle PWM values for difficult ESCs
+ * disarmed PWM values for difficult ESCs
*
*/
-uint16_t r_page_servo_idle[PX4IO_SERVO_COUNT] = { 900, 900, 900, 900, 900, 900, 900, 900 };
+uint16_t r_page_servo_disarmed[PX4IO_SERVO_COUNT] = { 0, 0, 0, 0, 0, 0, 0, 0 };
int
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
@@ -293,16 +293,15 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* copy channel data */
while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
- if (*values == 0)
- /* set to default */
- r_page_servo_control_min[offset] = 900;
-
- else if (*values > 1200)
- r_page_servo_control_min[offset] = 1200;
- else if (*values < 900)
- r_page_servo_control_min[offset] = 900;
- else
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values > PWM_HIGHEST_MIN) {
+ r_page_servo_control_min[offset] = PWM_HIGHEST_MIN;
+ } else if (*values < PWM_MIN) {
+ r_page_servo_control_min[offset] = PWM_MIN;
+ } else {
r_page_servo_control_min[offset] = *values;
+ }
offset++;
num_values--;
@@ -315,16 +314,15 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* copy channel data */
while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
- if (*values == 0)
- /* set to default */
- r_page_servo_control_max[offset] = 2100;
-
- else if (*values > 2100)
- r_page_servo_control_max[offset] = 2100;
- else if (*values < 1800)
- r_page_servo_control_max[offset] = 1800;
- else
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values > PWM_MAX) {
+ r_page_servo_control_max[offset] = PWM_MAX;
+ } else if (*values < PWM_LOWEST_MAX) {
+ r_page_servo_control_max[offset] = PWM_LOWEST_MAX;
+ } else {
r_page_servo_control_max[offset] = *values;
+ }
offset++;
num_values--;
@@ -332,21 +330,20 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
}
break;
- case PX4IO_PAGE_IDLE_PWM:
+ case PX4IO_PAGE_DISARMED_PWM:
/* copy channel data */
while ((offset < PX4IO_SERVO_COUNT) && (num_values > 0)) {
- if (*values == 0)
- /* set to default */
- r_page_servo_idle[offset] = 0;
-
- else if (*values < 900)
- r_page_servo_idle[offset] = 900;
- else if (*values > 2100)
- r_page_servo_idle[offset] = 2100;
- else
- r_page_servo_idle[offset] = *values;
+ if (*values == 0) {
+ /* ignore 0 */
+ } else if (*values < PWM_MIN) {
+ r_page_servo_disarmed[offset] = PWM_MIN;
+ } else if (*values > PWM_MAX) {
+ r_page_servo_disarmed[offset] = PWM_MAX;
+ } else {
+ r_page_servo_disarmed[offset] = *values;
+ }
/* flag the failsafe values as custom */
r_setup_arming |= PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE;
@@ -767,8 +764,8 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
case PX4IO_PAGE_CONTROL_MAX_PWM:
SELECT_PAGE(r_page_servo_control_max);
break;
- case PX4IO_PAGE_IDLE_PWM:
- SELECT_PAGE(r_page_servo_idle);
+ case PX4IO_PAGE_DISARMED_PWM:
+ SELECT_PAGE(r_page_servo_disarmed);
break;
default:
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
new file mode 100644
index 000000000..3187a4fa2
--- /dev/null
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 pwm_limit.c
+ *
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include "pwm_limit.h"
+#include <math.h>
+#include <stdbool.h>
+#include <drivers/drv_hrt.h>
+
+void pwm_limit_init(pwm_limit_t *limit)
+{
+ limit->state = LIMIT_STATE_OFF;
+ limit->time_armed = 0;
+ return;
+}
+
+void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
+{
+ /* first evaluate state changes */
+ switch (limit->state) {
+ case LIMIT_STATE_OFF:
+ if (armed)
+ limit->state = LIMIT_STATE_RAMP;
+ limit->time_armed = hrt_absolute_time();
+ break;
+ case LIMIT_STATE_INIT:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US)
+ limit->state = LIMIT_STATE_RAMP;
+ break;
+ case LIMIT_STATE_RAMP:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US + RAMP_TIME_US)
+ limit->state = LIMIT_STATE_ON;
+ break;
+ case LIMIT_STATE_ON:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ break;
+ default:
+ break;
+ }
+
+ unsigned progress;
+ uint16_t temp_pwm;
+
+ /* then set effective_pwm based on state */
+ switch (limit->state) {
+ case LIMIT_STATE_OFF:
+ case LIMIT_STATE_INIT:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = disarmed_pwm[i];
+ output[i] = 0.0f;
+ }
+ break;
+ case LIMIT_STATE_RAMP:
+
+ progress = (hrt_absolute_time() - INIT_TIME_US - limit->time_armed)*10000 / RAMP_TIME_US;
+ for (unsigned i=0; i<num_channels; i++) {
+
+ temp_pwm = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+ /* already follow user/controller input if higher than min_pwm */
+ effective_pwm[i] = (disarmed_pwm[i]*(10000-progress) + (temp_pwm > min_pwm[i] ? temp_pwm : min_pwm[i])*progress)/10000;
+ output[i] = (float)progress/10000.0f * output[i];
+ }
+ break;
+ case LIMIT_STATE_ON:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+ /* effective_output stays the same */
+ }
+ break;
+ default:
+ break;
+ }
+ return;
+}
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.h b/src/modules/systemlib/pwm_limit/pwm_limit.h
new file mode 100644
index 000000000..9974770be
--- /dev/null
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Julian Oes <joes@student.ethz.ch>
+ *
+ * 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 pwm_limit.h
+ *
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#ifndef PWM_LIMIT_H_
+#define PWM_LIMIT_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/*
+ * time for the ESCs to initialize
+ * (this is not actually needed if PWM is sent right after boot)
+ */
+#define INIT_TIME_US 500000
+/*
+ * time to slowly ramp up the ESCs
+ */
+#define RAMP_TIME_US 2500000
+
+typedef struct {
+ enum {
+ LIMIT_STATE_OFF = 0,
+ LIMIT_STATE_INIT,
+ LIMIT_STATE_RAMP,
+ LIMIT_STATE_ON
+ } state;
+ uint64_t time_armed;
+} pwm_limit_t;
+
+__BEGIN_DECLS
+
+__EXPORT void pwm_limit_init(pwm_limit_t *limit);
+
+__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
+
+__END_DECLS
+
+#endif /* PWM_LIMIT_H_ */
diff --git a/src/modules/uORB/topics/actuator_outputs.h b/src/modules/uORB/topics/actuator_outputs.h
index 30895ca83..446140423 100644
--- a/src/modules/uORB/topics/actuator_outputs.h
+++ b/src/modules/uORB/topics/actuator_outputs.h
@@ -60,7 +60,7 @@
struct actuator_outputs_s {
uint64_t timestamp; /**< output timestamp in us since system boot */
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
- int noutputs; /**< valid outputs */
+ unsigned noutputs; /**< valid outputs */
};
/**
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index c42a36c7f..b3975de9d 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -45,6 +45,7 @@
#include <stdbool.h>
#include <unistd.h>
#include <fcntl.h>
+#include <poll.h>
#include <sys/mount.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
@@ -71,16 +72,36 @@ usage(const char *reason)
warnx("%s", reason);
errx(1,
"usage:\n"
- "pwm [-v] [-d <device>] [-u <alt_rate>] [-c <channel group>] [-m chanmask ] [arm|disarm] [<channel_value> ...]\n"
- " -v Print information about the PWM device\n"
- " <device> PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n"
- " <alt_rate> PWM update rate for channels in <alt_channel_mask>\n"
- " <channel_group> Channel group that should update at the alternate rate (may be specified more than once)\n"
- " arm | disarm Arm or disarm the ouptut\n"
- " <channel_value>... PWM output values in microseconds to assign to the PWM outputs\n"
- " <chanmask> Directly supply alt rate channel mask (debug use only)\n"
+ "pwm arm|disarm|rate|min|max|disarmed|set|info ...\n"
"\n"
- "When -c is specified, any channel groups not listed with -c will update at the default rate.\n"
+ " arm Arm output\n"
+ " disarm Disarm output\n"
+ "\n"
+ " rate Configure PWM rates\n"
+ " [-g <channel group>] Channel group that should update at the alternate rate\n"
+ " [-m <chanmask> ] Directly supply channel mask\n"
+ " [-a] Configure all outputs\n"
+ " -r <alt_rate> PWM rate (50 to 400 Hz)\n"
+ "\n"
+ " min ... Configure minimum PWM values\n"
+ " max ... Configure maximum PWM values\n"
+ " disarmed ... Configure disarmed PWM values\n"
+ " [-c <channels>] Supply channels (e.g. 1234)\n"
+ " [-m <chanmask> ] Directly supply channel mask (e.g. 0xF)\n"
+ " [-a] Configure all outputs\n"
+ " -p <pwm value> PWM value\n"
+ "\n"
+ " set ... Directly set PWM values\n"
+ " [-c <channels>] Supply channels (e.g. 1234)\n"
+ " [-m <chanmask> ] Directly supply channel mask (e.g. 0xF)\n"
+ " [-a] Configure all outputs\n"
+ " [-e] Repeat setting the values until stopped\n"
+ " -p <pwm value> PWM value\n"
+ "\n"
+ " info Print information about the PWM device\n"
+ "\n"
+ " -v Print verbose information\n"
+ " -d <device> PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n"
);
}
@@ -92,152 +113,370 @@ pwm_main(int argc, char *argv[])
unsigned alt_rate = 0;
uint32_t alt_channel_groups = 0;
bool alt_channels_set = false;
- bool print_info = false;
+ bool print_verbose = false;
+ bool repeated_pwm_output = false;
int ch;
int ret;
char *ep;
+ uint32_t set_mask = 0;
unsigned group;
- int32_t set_mask = -1;
+ unsigned long channels;
+ unsigned single_ch = 0;
+ unsigned pwm_value = 0;
- if (argc < 2)
+ if (argc < 1)
usage(NULL);
- while ((ch = getopt(argc, argv, "c:d:u:vm:")) != EOF) {
+ while ((ch = getopt(argc-1, &argv[1], "d:vc:g:m:ap:r:e")) != EOF) {
switch (ch) {
+
+ case 'd':
+ if (NULL == strstr(optarg, "/dev/")) {
+ warnx("device %s not valid", optarg);
+ usage(NULL);
+ }
+ dev = optarg;
+ break;
+
+ case 'v':
+ print_verbose = true;
+ break;
+
case 'c':
+ /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */
+ channels = strtoul(optarg, &ep, 0);
+
+ while ((single_ch = channels % 10)) {
+
+ set_mask |= 1<<(single_ch-1);
+ channels /= 10;
+ }
+ break;
+
+ case 'g':
group = strtoul(optarg, &ep, 0);
if ((*ep != '\0') || (group >= 32))
usage("bad channel_group value");
alt_channel_groups |= (1 << group);
alt_channels_set = true;
+ warnx("alt channels set, group: %d", group);
break;
- case 'd':
- dev = optarg;
+ case 'm':
+ /* Read in mask directly */
+ set_mask = strtoul(optarg, &ep, 0);
+ if (*ep != '\0')
+ usage("bad set_mask value");
break;
- case 'u':
- alt_rate = strtol(optarg, &ep, 0);
+ case 'a':
+ for (unsigned i = 0; i<PWM_OUTPUT_MAX_CHANNELS; i++) {
+ set_mask |= 1<<i;
+ }
+ break;
+ case 'p':
+ pwm_value = strtoul(optarg, &ep, 0);
if (*ep != '\0')
- usage("bad alt_rate value");
+ usage("bad PWM value provided");
break;
-
- case 'm':
- set_mask = strtol(optarg, &ep, 0);
+ case 'r':
+ alt_rate = strtoul(optarg, &ep, 0);
if (*ep != '\0')
- usage("bad set_mask value");
+ usage("bad alternative rate provided");
break;
-
- case 'v':
- print_info = true;
+ case 'e':
+ repeated_pwm_output = true;
break;
-
default:
- usage(NULL);
+ break;
+ }
+ }
+
+ if (print_verbose && set_mask > 0) {
+ warnx("Chose channels: ");
+ printf(" ");
+ for (unsigned i = 0; i<PWM_OUTPUT_MAX_CHANNELS; i++) {
+ if (set_mask & 1<<i)
+ printf("%d ", i+1);
}
+ printf("\n");
}
- argc -= optind;
- argv += optind;
/* open for ioctl only */
int fd = open(dev, 0);
if (fd < 0)
err(1, "can't open %s", dev);
- /* change alternate PWM rate */
- if (alt_rate > 0) {
- ret = ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, alt_rate);
+ /* get the number of servo channels */
+ unsigned servo_count;
+ ret = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count);
+ if (ret != OK)
+ err(1, "PWM_SERVO_GET_COUNT");
+
+ if (!strcmp(argv[1], "arm")) {
+ /* tell IO that its ok to disable its safety with the switch */
+ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
if (ret != OK)
- err(1, "PWM_SERVO_SET_UPDATE_RATE (check rate for sanity)");
- }
+ err(1, "PWM_SERVO_SET_ARM_OK");
+ /* tell IO that the system is armed (it will output values if safety is off) */
+ ret = ioctl(fd, PWM_SERVO_ARM, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_ARM");
+
+ if (print_verbose)
+ warnx("Outputs armed");
+ exit(0);
- /* directly supplied channel mask */
- if (set_mask != -1) {
- ret = ioctl(fd, PWM_SERVO_SELECT_UPDATE_RATE, set_mask);
+ } else if (!strcmp(argv[1], "disarm")) {
+ /* disarm, but do not revoke the SET_ARM_OK flag */
+ ret = ioctl(fd, PWM_SERVO_DISARM, 0);
if (ret != OK)
- err(1, "PWM_SERVO_SELECT_UPDATE_RATE");
- }
+ err(1, "PWM_SERVO_DISARM");
+
+ if (print_verbose)
+ warnx("Outputs disarmed");
+ exit(0);
+
+ } else if (!strcmp(argv[1], "rate")) {
+
+ /* change alternate PWM rate */
+ if (alt_rate > 0) {
+ ret = ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, alt_rate);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_UPDATE_RATE (check rate for sanity)");
+ }
- /* assign alternate rate to channel groups */
- if (alt_channels_set) {
- uint32_t mask = 0;
+ /* directly supplied channel mask */
+ if (set_mask > 0) {
+ ret = ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, set_mask);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_SELECT_UPDATE_RATE");
+ }
- for (unsigned group = 0; group < 32; group++) {
- if ((1 << group) & alt_channel_groups) {
- uint32_t group_mask;
+ /* assign alternate rate to channel groups */
+ if (alt_channels_set) {
+ uint32_t mask = 0;
- ret = ioctl(fd, PWM_SERVO_GET_RATEGROUP(group), (unsigned long)&group_mask);
- if (ret != OK)
- err(1, "PWM_SERVO_GET_RATEGROUP(%u)", group);
+ for (group = 0; group < 32; group++) {
+ if ((1 << group) & alt_channel_groups) {
+ uint32_t group_mask;
- mask |= group_mask;
+ ret = ioctl(fd, PWM_SERVO_GET_RATEGROUP(group), (unsigned long)&group_mask);
+ if (ret != OK)
+ err(1, "PWM_SERVO_GET_RATEGROUP(%u)", group);
+
+ mask |= group_mask;
+ }
}
+
+ ret = ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, mask);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_SELECT_UPDATE_RATE");
}
+ exit(0);
- ret = ioctl(fd, PWM_SERVO_SELECT_UPDATE_RATE, mask);
- if (ret != OK)
- err(1, "PWM_SERVO_SELECT_UPDATE_RATE");
- }
+ } else if (!strcmp(argv[1], "min")) {
+
+ if (set_mask == 0) {
+ usage("no channels set");
+ }
+ if (pwm_value == 0)
+ usage("no PWM value provided");
- /* iterate remaining arguments */
- unsigned nchannels = 0;
- unsigned channel[8] = {0};
- while (argc--) {
- const char *arg = argv[0];
- argv++;
- if (!strcmp(arg, "arm")) {
- /* tell IO that its ok to disable its safety with the switch */
- ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 0};
+
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ pwm_values.values[i] = pwm_value;
+ if (print_verbose)
+ warnx("Channel %d: min PWM: %d", i+1, pwm_value);
+ }
+ pwm_values.channel_count++;
+ }
+
+ if (pwm_values.channel_count == 0) {
+ usage("no PWM values added");
+ } else {
+
+ ret = ioctl(fd, PWM_SERVO_SET_MIN_PWM, (long unsigned int)&pwm_values);
if (ret != OK)
- err(1, "PWM_SERVO_SET_ARM_OK");
- /* tell IO that the system is armed (it will output values if safety is off) */
- ret = ioctl(fd, PWM_SERVO_ARM, 0);
+ errx(ret, "failed setting min values");
+ }
+ exit(0);
+
+ } else if (!strcmp(argv[1], "max")) {
+
+ if (set_mask == 0) {
+ usage("no channels set");
+ }
+ if (pwm_value == 0)
+ usage("no PWM value provided");
+
+ struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 0};
+
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ pwm_values.values[i] = pwm_value;
+ if (print_verbose)
+ warnx("Channel %d: max PWM: %d", i+1, pwm_value);
+ }
+ pwm_values.channel_count++;
+ }
+
+ if (pwm_values.channel_count == 0) {
+ usage("no PWM values added");
+ } else {
+
+ ret = ioctl(fd, PWM_SERVO_SET_MAX_PWM, (long unsigned int)&pwm_values);
if (ret != OK)
- err(1, "PWM_SERVO_ARM");
- continue;
+ errx(ret, "failed setting max values");
}
- if (!strcmp(arg, "disarm")) {
- /* disarm, but do not revoke the SET_ARM_OK flag */
- ret = ioctl(fd, PWM_SERVO_DISARM, 0);
+ exit(0);
+
+ } else if (!strcmp(argv[1], "disarmed")) {
+
+ if (set_mask == 0) {
+ usage("no channels set");
+ }
+ if (pwm_value == 0)
+ usage("no PWM value provided");
+
+ struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 0};
+
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ pwm_values.values[i] = pwm_value;
+ if (print_verbose)
+ warnx("Channel %d: disarmed PWM: %d", i+1, pwm_value);
+ }
+ pwm_values.channel_count++;
+ }
+
+ if (pwm_values.channel_count == 0) {
+ usage("no PWM values added");
+ } else {
+
+ ret = ioctl(fd, PWM_SERVO_SET_DISARMED_PWM, (long unsigned int)&pwm_values);
if (ret != OK)
- err(1, "PWM_SERVO_DISARM");
- continue;
+ errx(ret, "failed setting disarmed values");
}
- unsigned pwm_value = strtol(arg, &ep, 0);
- if (*ep == '\0') {
- if (nchannels > sizeof(channel) / sizeof(channel[0]))
- err(1, "too many pwm values (max %d)", sizeof(channel) / sizeof(channel[0]));
+ exit(0);
- channel[nchannels] = pwm_value;
- nchannels++;
+ } else if (!strcmp(argv[1], "set")) {
- continue;
+ if (set_mask == 0) {
+ usage("no channels set");
}
- usage("unrecognized option");
- }
+ if (pwm_value == 0)
+ usage("no PWM value provided");
- /* print verbose info */
- if (print_info) {
- /* get the number of servo channels */
- unsigned count;
- ret = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&count);
- if (ret != OK)
- err(1, "PWM_SERVO_GET_COUNT");
+ /* perform PWM output */
+
+ if (repeated_pwm_output) {
+
+ /* Open console directly to grab CTRL-C signal */
+ struct pollfd fds;
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
+ while (1) {
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), pwm_value);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ /* abort on user request */
+ char c;
+ ret = poll(&fds, 1, 0);
+ if (ret > 0) {
+
+ read(0, &c, 1);
+ if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("User abort\n");
+ exit(0);
+ }
+ }
+ }
+ } else {
+ /* only set the values once */
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), pwm_value);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+ }
+ exit(0);
+
+
+ } else if (!strcmp(argv[1], "info")) {
+
+ printf("device: %s\n", dev);
+
+ uint32_t info_default_rate;
+ uint32_t info_alt_rate;
+ uint32_t info_alt_rate_mask;
+
+ ret = ioctl(fd, PWM_SERVO_GET_DEFAULT_UPDATE_RATE, (unsigned long)&info_default_rate);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_DEFAULT_UPDATE_RATE");
+ }
+
+ ret = ioctl(fd, PWM_SERVO_GET_UPDATE_RATE, (unsigned long)&info_alt_rate);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_UPDATE_RATE");
+ }
+
+ ret = ioctl(fd, PWM_SERVO_GET_SELECT_UPDATE_RATE, (unsigned long)&info_alt_rate_mask);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_SELECT_UPDATE_RATE");
+ }
+
+ struct pwm_output_values disarmed_pwm;
+ struct pwm_output_values min_pwm;
+ struct pwm_output_values max_pwm;
+
+ ret = ioctl(fd, PWM_SERVO_GET_DISARMED_PWM, (unsigned long)&disarmed_pwm);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_DISARMED_PWM");
+ }
+ ret = ioctl(fd, PWM_SERVO_GET_MIN_PWM, (unsigned long)&min_pwm);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_MIN_PWM");
+ }
+ ret = ioctl(fd, PWM_SERVO_GET_MAX_PWM, (unsigned long)&max_pwm);
+ if (ret != OK) {
+ err(1, "PWM_SERVO_GET_MAX_PWM");
+ }
/* print current servo values */
- for (unsigned i = 0; i < count; i++) {
+ for (unsigned i = 0; i < servo_count; i++) {
servo_position_t spos;
ret = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&spos);
if (ret == OK) {
- printf("channel %u: %uus\n", i, spos);
+ printf("channel %u: %u us", i+1, spos);
+
+ if (info_alt_rate_mask & (1<<i))
+ printf(" (alternative rate: %d Hz", info_alt_rate);
+ else
+ printf(" (default rate: %d Hz", info_default_rate);
+
+
+ printf(" disarmed; %d us, min: %d us, max: %d us)", disarmed_pwm.values[i], min_pwm.values[i], max_pwm.values[i]);
+ printf("\n");
} else {
printf("%u: ERROR\n", i);
}
}
-
/* print rate groups */
- for (unsigned i = 0; i < count; i++) {
+ for (unsigned i = 0; i < servo_count; i++) {
uint32_t group_mask;
ret = ioctl(fd, PWM_SERVO_GET_RATEGROUP(i), (unsigned long)&group_mask);
@@ -247,44 +486,14 @@ pwm_main(int argc, char *argv[])
printf("channel group %u: channels", i);
for (unsigned j = 0; j < 32; j++)
if (group_mask & (1 << j))
- printf(" %u", j);
+ printf(" %u", j+1);
printf("\n");
}
}
- fflush(stdout);
- }
-
- /* perform PWM output */
- if (nchannels) {
-
- /* Open console directly to grab CTRL-C signal */
- int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
- if (!console)
- err(1, "failed opening console");
-
- warnx("Press CTRL-C or 'c' to abort.");
+ exit(0);
- while (1) {
- for (int i = 0; i < nchannels; i++) {
- ret = ioctl(fd, PWM_SERVO_SET(i), channel[i]);
- if (ret != OK)
- err(1, "PWM_SERVO_SET(%d)", i);
- }
-
- /* abort on user request */
- char c;
- if (read(console, &c, 1) == 1) {
- if (c == 0x03 || c == 0x63 || c == 'q') {
- warnx("User abort\n");
- close(console);
- exit(0);
- }
- }
-
- /* rate limit to ~ 20 Hz */
- usleep(50000);
- }
}
+ usage("specify arm|disarm|rate|min|max|disarmed|set|info");
+ return 0;
+}
- exit(0);
-} \ No newline at end of file