PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <px4_platform_common/defines.h>
#include <stdint.h>
#include <sys/ioctl.h>
#include <board_config.h>
#include "drv_orb_dev.h"
Go to the source code of this file.
Classes | |
struct | pwm_output_values |
struct | pwm_output_rc_config |
RC config values for a channel. More... | |
Macros | |
#define | PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output" |
Path for the default PWM output device. More... | |
#define | PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0" |
#define | PWM_OUTPUT_MAX_CHANNELS 16 |
#define | PWM_LOWEST_MIN 90 |
Lowest minimum PWM in us. More... | |
#define | PWM_MOTOR_OFF 900 |
Default value for a shutdown motor. More... | |
#define | PWM_DEFAULT_MIN 1000 |
Default minimum PWM in us. More... | |
#define | PWM_HIGHEST_MIN 1600 |
Highest PWM allowed as the minimum PWM. More... | |
#define | PWM_HIGHEST_MAX 2150 |
Highest maximum PWM in us. More... | |
#define | PWM_DEFAULT_MAX 2000 |
Default maximum PWM in us. More... | |
#define | PWM_DEFAULT_TRIM 0 |
Default trim PWM in us. More... | |
#define | PWM_LOWEST_MAX 200 |
Lowest PWM allowed as the maximum PWM. More... | |
#define | PWM_IGNORE_THIS_CHANNEL UINT16_MAX |
Do not output a channel with this value. More... | |
#define | _PWM_SERVO_BASE 0x2a00 |
#define | PWM_SERVO_ARM _PX4_IOC(_PWM_SERVO_BASE, 0) |
arm all servo outputs handle by this driver More... | |
#define | PWM_SERVO_DISARM _PX4_IOC(_PWM_SERVO_BASE, 1) |
disarm all servo outputs (stop generating pulses) More... | |
#define | PWM_SERVO_GET_DEFAULT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 2) |
get default servo update rate More... | |
#define | PWM_SERVO_SET_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 3) |
set alternate servo update rate More... | |
#define | PWM_SERVO_GET_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 4) |
get alternate servo update rate More... | |
#define | PWM_SERVO_GET_COUNT _PX4_IOC(_PWM_SERVO_BASE, 5) |
get the number of servos in *(unsigned *)arg More... | |
#define | PWM_SERVO_SET_SELECT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 6) |
selects servo update rates, one bit per servo. More... | |
#define | PWM_SERVO_GET_SELECT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 7) |
check the selected update rates More... | |
#define | PWM_SERVO_SET_ARM_OK _PX4_IOC(_PWM_SERVO_BASE, 8) |
set the 'ARM ok' bit, which activates the safety switch More... | |
#define | PWM_SERVO_CLEAR_ARM_OK _PX4_IOC(_PWM_SERVO_BASE, 9) |
clear the 'ARM ok' bit, which deactivates the safety switch More... | |
#define | DSM_BIND_START _PX4_IOC(_PWM_SERVO_BASE, 10) |
start DSM bind More... | |
#define | DSM_BIND_POWER_UP _PX4_IOC(_PWM_SERVO_BASE, 11) |
power up DSM receiver More... | |
#define | PWM_SERVO_SET_FAILSAFE_PWM _PX4_IOC(_PWM_SERVO_BASE, 12) |
set the PWM value for failsafe More... | |
#define | PWM_SERVO_GET_FAILSAFE_PWM _PX4_IOC(_PWM_SERVO_BASE, 13) |
get the PWM value for failsafe More... | |
#define | PWM_SERVO_SET_DISARMED_PWM _PX4_IOC(_PWM_SERVO_BASE, 14) |
set the PWM value when disarmed - should be no PWM (zero) by default More... | |
#define | PWM_SERVO_GET_DISARMED_PWM _PX4_IOC(_PWM_SERVO_BASE, 15) |
get the PWM value when disarmed More... | |
#define | PWM_SERVO_SET_MIN_PWM _PX4_IOC(_PWM_SERVO_BASE, 16) |
set the minimum PWM value the output will send More... | |
#define | PWM_SERVO_GET_MIN_PWM _PX4_IOC(_PWM_SERVO_BASE, 17) |
get the minimum PWM value the output will send More... | |
#define | PWM_SERVO_SET_MAX_PWM _PX4_IOC(_PWM_SERVO_BASE, 18) |
set the maximum PWM value the output will send More... | |
#define | PWM_SERVO_GET_MAX_PWM _PX4_IOC(_PWM_SERVO_BASE, 19) |
get the maximum PWM value the output will send More... | |
#define | PWM_SERVO_SET_TRIM_PWM _PX4_IOC(_PWM_SERVO_BASE, 20) |
set the TRIM value the output will send More... | |
#define | PWM_SERVO_GET_TRIM_PWM _PX4_IOC(_PWM_SERVO_BASE, 21) |
get the TRIM value the output will send More... | |
#define | PWM_SERVO_SET_COUNT _PX4_IOC(_PWM_SERVO_BASE, 22) |
set the number of servos in (unsigned)arg - allows change of split between servos and GPIO More... | |
#define | PWM_SERVO_SET_DISABLE_LOCKDOWN _PX4_IOC(_PWM_SERVO_BASE, 23) |
set the lockdown override flag to enable outputs in HIL More... | |
#define | PWM_SERVO_GET_DISABLE_LOCKDOWN _PX4_IOC(_PWM_SERVO_BASE, 24) |
get the lockdown override flag to enable outputs in HIL More... | |
#define | PWM_SERVO_SET_FORCE_SAFETY_OFF _PX4_IOC(_PWM_SERVO_BASE, 25) |
force safety switch off (to disable use of safety switch) More... | |
#define | PWM_SERVO_SET_FORCE_FAILSAFE _PX4_IOC(_PWM_SERVO_BASE, 26) |
force failsafe mode (failsafe values are set immediately even if failsafe condition not met) More... | |
#define | PWM_SERVO_SET_TERMINATION_FAILSAFE _PX4_IOC(_PWM_SERVO_BASE, 27) |
make failsafe non-recoverable (termination) if it occurs More... | |
#define | PWM_SERVO_SET_FORCE_SAFETY_ON _PX4_IOC(_PWM_SERVO_BASE, 28) |
force safety switch on (to enable use of safety switch) More... | |
#define | PWM_SERVO_SET_OVERRIDE_IMMEDIATE _PX4_IOC(_PWM_SERVO_BASE, 32) |
setup OVERRIDE_IMMEDIATE behaviour on FMU fail More... | |
#define | PWM_SERVO_SET_SBUS_RATE _PX4_IOC(_PWM_SERVO_BASE, 33) |
set SBUS output frame rate in Hz More... | |
#define | PWM_SERVO_MODE_NONE 0 |
set auxillary output mode. More... | |
#define | PWM_SERVO_MODE_1PWM 1 |
#define | PWM_SERVO_MODE_2PWM 2 |
#define | PWM_SERVO_MODE_2PWM2CAP 3 |
#define | PWM_SERVO_MODE_3PWM 4 |
#define | PWM_SERVO_MODE_3PWM1CAP 5 |
#define | PWM_SERVO_MODE_4PWM 6 |
#define | PWM_SERVO_MODE_4PWM1CAP 7 |
#define | PWM_SERVO_MODE_4PWM2CAP 8 |
#define | PWM_SERVO_MODE_5PWM 9 |
#define | PWM_SERVO_MODE_5PWM1CAP 10 |
#define | PWM_SERVO_MODE_6PWM 11 |
#define | PWM_SERVO_MODE_8PWM 12 |
#define | PWM_SERVO_MODE_14PWM 13 |
#define | PWM_SERVO_MODE_4CAP 14 |
#define | PWM_SERVO_MODE_5CAP 15 |
#define | PWM_SERVO_MODE_6CAP 16 |
#define | PWM_SERVO_ENTER_TEST_MODE 17 |
#define | PWM_SERVO_EXIT_TEST_MODE 18 |
#define | PWM_SERVO_SET_MODE _PX4_IOC(_PWM_SERVO_BASE, 34) |
#define | PWM_SERVO_SET(_servo) _PX4_IOC(_PWM_SERVO_BASE, 0x30 + _servo) |
set a single servo to a specific value More... | |
#define | PWM_SERVO_GET(_servo) _PX4_IOC(_PWM_SERVO_BASE, 0x50 + _servo) |
get a single specific servo value More... | |
#define | PWM_SERVO_GET_RATEGROUP(_n) _PX4_IOC(_PWM_SERVO_BASE, 0x70 + _n) |
get the _n'th rate group's channels; *(uint32_t *)arg returns a bitmap of channels whose update rates must be the same. More... | |
#define | PWM_RATE_ONESHOT 0u |
specific rates for configuring the timer for OneShot or PWM More... | |
#define | PWM_RATE_LOWER_LIMIT 1u |
#define | PWM_RATE_UPPER_LIMIT 10000u |
#define | DSHOT1200 1200000u |
Dshot PWM frequency. More... | |
#define | DSHOT600 600000u |
#define | DSHOT300 300000u |
#define | DSHOT150 150000u |
#define | DSHOT_MAX_THROTTLE 1999 |
Typedefs | |
typedef uint16_t | servo_position_t |
Servo output signal type, value is actual servo output pulse width in microseconds. More... | |
Functions | |
__EXPORT int | up_pwm_servo_init (uint32_t channel_mask) |
Intialise the PWM servo outputs using the specified configuration. More... | |
__EXPORT void | up_pwm_servo_deinit (void) |
De-initialise the PWM servo outputs. More... | |
__EXPORT void | up_pwm_servo_arm (bool armed) |
Arm or disarm servo outputs. More... | |
__EXPORT int | up_pwm_servo_set_rate (unsigned rate) |
Set the servo update rate for all rate groups. More... | |
__EXPORT uint32_t | up_pwm_servo_get_rate_group (unsigned group) |
Get a bitmap of output channels assigned to a given rate group. More... | |
__EXPORT int | up_pwm_servo_set_rate_group_update (unsigned group, unsigned rate) |
Set the update rate for a given rate group. More... | |
__EXPORT void | up_pwm_update (void) |
Trigger all timer's channels in Oneshot mode to fire the oneshot with updated values. More... | |
__EXPORT int | up_pwm_servo_set (unsigned channel, servo_position_t value) |
Set the current output value for a channel. More... | |
__EXPORT servo_position_t | up_pwm_servo_get (unsigned channel) |
Get the current output value for a channel. More... | |
__EXPORT int | up_dshot_init (uint32_t channel_mask, unsigned dshot_pwm_freq) |
Intialise the Dshot outputs using the specified configuration. More... | |
__EXPORT void | up_dshot_motor_data_set (unsigned channel, uint16_t throttle, bool telemetry) |
Set the current dshot throttle value for a channel (motor). More... | |
__EXPORT void | up_dshot_motor_command (unsigned channel, uint16_t command, bool telemetry) |
Send DShot command to a channel (motor). More... | |
__EXPORT void | up_dshot_trigger (void) |
Trigger dshot data transfer. More... | |
__EXPORT int | up_dshot_arm (bool armed) |
Arm or disarm dshot outputs (This will enable/disable complete timer for safety purpose.). More... | |
#define _PWM_SERVO_BASE 0x2a00 |
Definition at line 153 of file drv_pwm_output.h.
#define DSHOT1200 1200000u |
Dshot PWM frequency.
Definition at line 296 of file drv_pwm_output.h.
Referenced by DShotOutput::update_dshot_out_state().
#define DSHOT150 150000u |
Definition at line 299 of file drv_pwm_output.h.
Referenced by DShotOutput::update_dshot_out_state().
#define DSHOT300 300000u |
Definition at line 298 of file drv_pwm_output.h.
Referenced by DShotOutput::update_dshot_out_state().
#define DSHOT600 600000u |
Definition at line 297 of file drv_pwm_output.h.
Referenced by DShotOutput::update_dshot_out_state().
#define DSHOT_MAX_THROTTLE 1999 |
Definition at line 301 of file drv_pwm_output.h.
Referenced by DShotOutput::DShotOutput(), DShotOutput::update_params(), and DShotOutput::updateOutputs().
#define DSM_BIND_POWER_UP _PX4_IOC(_PWM_SERVO_BASE, 11) |
power up DSM receiver
Definition at line 189 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl().
#define DSM_BIND_START _PX4_IOC(_PWM_SERVO_BASE, 10) |
start DSM bind
Definition at line 186 of file drv_pwm_output.h.
Referenced by PX4IO::dsm_bind_ioctl(), PX4IO::ioctl(), and PX4IO::set_update_rate().
#define PWM_DEFAULT_MAX 2000 |
Default maximum PWM in us.
Definition at line 106 of file drv_pwm_output.h.
Referenced by Simulator::actuator_controls_from_outputs(), MissionFeasibilityChecker::checkMissionItemValidity(), esc_calib_main(), MixerTest::mixerTest(), PX4FMU::PX4FMU(), Sih::read_motors(), MavlinkStreamHILActuatorControls::send(), Tiltrotor::update_transition_state(), and VtolType::VtolType().
#define PWM_DEFAULT_MIN 1000 |
Default minimum PWM in us.
Definition at line 91 of file drv_pwm_output.h.
Referenced by Simulator::actuator_controls_from_outputs(), esc_calib_main(), MixerTest::mixerTest(), PX4FMU::PX4FMU(), Sih::read_motors(), MavlinkStreamHILActuatorControls::send(), Tiltrotor::update_transition_state(), and VtolAttitudeControl::VtolAttitudeControl().
#define PWM_DEFAULT_TRIM 0 |
Default trim PWM in us.
Definition at line 111 of file drv_pwm_output.h.
#define PWM_HIGHEST_MAX 2150 |
Highest maximum PWM in us.
Definition at line 101 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and registers_set().
#define PWM_HIGHEST_MIN 1600 |
Highest PWM allowed as the minimum PWM.
Definition at line 96 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PX4FMU::pwm_ioctl(), and registers_set().
#define PWM_IGNORE_THIS_CHANNEL UINT16_MAX |
Do not output a channel with this value.
Definition at line 123 of file drv_pwm_output.h.
Referenced by registers_set().
#define PWM_LOWEST_MAX 200 |
Lowest PWM allowed as the maximum PWM.
Definition at line 116 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PX4FMU::pwm_ioctl(), and registers_set().
#define PWM_LOWEST_MIN 90 |
Lowest minimum PWM in us.
Definition at line 81 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PX4IO::ioctl(), MixerTest::mixerTest(), PX4FMU::pwm_ioctl(), and registers_set().
#define PWM_MOTOR_OFF 900 |
Default value for a shutdown motor.
Definition at line 86 of file drv_pwm_output.h.
Referenced by MixerTest::mixerTest(), VtolType::set_idle_fw(), and VtolType::VtolType().
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0" |
Definition at line 63 of file drv_pwm_output.h.
Referenced by VtolType::apply_pwm_limits(), do_esc_calibration(), esc_calib_main(), VtolType::init(), PX4IO::init(), pwm_main(), PX4IO::task_main(), test_ppm_loopback(), and test_servo().
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output" |
Path for the default PWM output device.
Note that on systems with more than one PWM output path (e.g. PX4FMU with PX4IO connected) there may be other devices that respond to this protocol.
Definition at line 62 of file drv_pwm_output.h.
Referenced by DShotOutput::init(), PX4FMU::init(), DShotOutput::~DShotOutput(), and PX4FMU::~PX4FMU().
#define PWM_OUTPUT_MAX_CHANNELS 16 |
Definition at line 65 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PWMSim::ioctl(), PX4IO::ioctl(), pwm_main(), and test_servo().
#define PWM_RATE_LOWER_LIMIT 1u |
Definition at line 292 of file drv_pwm_output.h.
#define PWM_RATE_ONESHOT 0u |
specific rates for configuring the timer for OneShot or PWM
Definition at line 291 of file drv_pwm_output.h.
#define PWM_RATE_UPPER_LIMIT 10000u |
Definition at line 293 of file drv_pwm_output.h.
#define PWM_SERVO_ARM _PX4_IOC(_PWM_SERVO_BASE, 0) |
arm all servo outputs handle by this driver
Definition at line 156 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), esc_calib_main(), PWMSim::ioctl(), PX4IO::ioctl(), prepare(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), PX4IO::set_update_rate(), PX4FMU::test(), and test_servo().
#define PWM_SERVO_CLEAR_ARM_OK _PX4_IOC(_PWM_SERVO_BASE, 9) |
clear the 'ARM ok' bit, which deactivates the safety switch
Definition at line 183 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), UavcanNode::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), and PX4FMU::pwm_ioctl().
#define PWM_SERVO_DISARM _PX4_IOC(_PWM_SERVO_BASE, 1) |
disarm all servo outputs (stop generating pulses)
Definition at line 159 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), esc_calib_main(), PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_ENTER_TEST_MODE 17 |
Definition at line 267 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), motor_ramp_thread_main(), PX4FMU::pwm_ioctl(), pwm_main(), and PX4FMU::test().
#define PWM_SERVO_EXIT_TEST_MODE 18 |
Definition at line 268 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), motor_ramp_thread_main(), PX4FMU::pwm_ioctl(), pwm_main(), and PX4FMU::test().
#define PWM_SERVO_GET | ( | _servo | ) | _PX4_IOC(_PWM_SERVO_BASE, 0x50 + _servo) |
get a single specific servo value
Definition at line 283 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), motor_ramp_thread_main(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), PX4IO::set_update_rate(), PX4FMU::test(), test_ppm_loopback(), and test_servo().
#define PWM_SERVO_GET_COUNT _PX4_IOC(_PWM_SERVO_BASE, 5) |
get the number of servos in *(unsigned *)arg
Definition at line 171 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PWMSim::ioctl(), PX4IO::ioctl(), motor_ramp_thread_main(), prepare(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), DShotOutput::pwm_ioctl(), pwm_main(), PX4IO::set_update_rate(), PX4FMU::test(), test_ppm_loopback(), and test_servo().
#define PWM_SERVO_GET_DEFAULT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 2) |
get default servo update rate
Definition at line 162 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _PX4_IOC(_PWM_SERVO_BASE, 24) |
get the lockdown override flag to enable outputs in HIL
Definition at line 229 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl().
#define PWM_SERVO_GET_DISARMED_PWM _PX4_IOC(_PWM_SERVO_BASE, 15) |
get the PWM value when disarmed
Definition at line 201 of file drv_pwm_output.h.
Referenced by VtolType::init(), PWMSim::ioctl(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_FAILSAFE_PWM _PX4_IOC(_PWM_SERVO_BASE, 13) |
get the PWM value for failsafe
Definition at line 195 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_MAX_PWM _PX4_IOC(_PWM_SERVO_BASE, 19) |
get the maximum PWM value the output will send
Definition at line 213 of file drv_pwm_output.h.
Referenced by VtolType::init(), PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_MIN_PWM _PX4_IOC(_PWM_SERVO_BASE, 17) |
get the minimum PWM value the output will send
Definition at line 207 of file drv_pwm_output.h.
Referenced by VtolType::init(), PWMSim::ioctl(), PX4IO::ioctl(), motor_ramp_thread_main(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_RATEGROUP | ( | _n | ) | _PX4_IOC(_PWM_SERVO_BASE, 0x70 + _n) |
get the _n'th rate group's channels; *(uint32_t *)arg returns a bitmap of channels whose update rates must be the same.
Definition at line 288 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_SELECT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 7) |
check the selected update rates
Definition at line 177 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_TRIM_PWM _PX4_IOC(_PWM_SERVO_BASE, 21) |
get the TRIM value the output will send
Definition at line 219 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_GET_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 4) |
get alternate servo update rate
Definition at line 168 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_MODE_14PWM 13 |
Definition at line 263 of file drv_pwm_output.h.
#define PWM_SERVO_MODE_1PWM 1 |
Definition at line 251 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_2PWM 2 |
Definition at line 252 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_2PWM2CAP 3 |
Definition at line 253 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_3PWM 4 |
Definition at line 254 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_3PWM1CAP 5 |
Definition at line 255 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_4CAP 14 |
Definition at line 264 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_4PWM 6 |
Definition at line 256 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_4PWM1CAP 7 |
Definition at line 257 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_4PWM2CAP 8 |
Definition at line 258 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), DShotOutput::pwm_ioctl(), and CameraCapture::set_capture_control().
#define PWM_SERVO_MODE_5CAP 15 |
Definition at line 265 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_5PWM 9 |
Definition at line 259 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_5PWM1CAP 10 |
Definition at line 260 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_6CAP 16 |
Definition at line 266 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_6PWM 11 |
Definition at line 261 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_8PWM 12 |
Definition at line 262 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_MODE_NONE 0 |
set auxillary output mode.
These correspond to enum Mode in px4fmu/fmu.cpp
Definition at line 250 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_SET | ( | _servo | ) | _PX4_IOC(_PWM_SERVO_BASE, 0x30 + _servo) |
set a single servo to a specific value
Definition at line 280 of file drv_pwm_output.h.
Referenced by esc_calib_main(), PX4IO::ioctl(), motor_ramp_thread_main(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), set_out(), PX4FMU::test(), test_ppm_loopback(), and test_servo().
#define PWM_SERVO_SET_ARM_OK _PX4_IOC(_PWM_SERVO_BASE, 8) |
set the 'ARM ok' bit, which activates the safety switch
Definition at line 180 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), esc_calib_main(), UavcanNode::ioctl(), PX4IO::ioctl(), prepare(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), PX4IO::set_update_rate(), and test_servo().
#define PWM_SERVO_SET_COUNT _PX4_IOC(_PWM_SERVO_BASE, 22) |
set the number of servos in (unsigned)arg - allows change of split between servos and GPIO
Definition at line 223 of file drv_pwm_output.h.
Referenced by PX4FMU::pwm_ioctl(), and DShotOutput::pwm_ioctl().
#define PWM_SERVO_SET_DISABLE_LOCKDOWN _PX4_IOC(_PWM_SERVO_BASE, 23) |
set the lockdown override flag to enable outputs in HIL
Definition at line 226 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), and PX4IO::set_update_rate().
#define PWM_SERVO_SET_DISARMED_PWM _PX4_IOC(_PWM_SERVO_BASE, 14) |
set the PWM value when disarmed - should be no PWM (zero) by default
Definition at line 198 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), and test_ppm_loopback().
#define PWM_SERVO_SET_FAILSAFE_PWM _PX4_IOC(_PWM_SERVO_BASE, 12) |
set the PWM value for failsafe
Definition at line 192 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_SET_FORCE_FAILSAFE _PX4_IOC(_PWM_SERVO_BASE, 26) |
force failsafe mode (failsafe values are set immediately even if failsafe condition not met)
Definition at line 235 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), and pwm_main().
#define PWM_SERVO_SET_FORCE_SAFETY_OFF _PX4_IOC(_PWM_SERVO_BASE, 25) |
force safety switch off (to disable use of safety switch)
Definition at line 232 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), UavcanNode::ioctl(), PX4IO::ioctl(), prepare(), PX4FMU::pwm_ioctl(), and px4io_main().
#define PWM_SERVO_SET_FORCE_SAFETY_ON _PX4_IOC(_PWM_SERVO_BASE, 28) |
force safety switch on (to enable use of safety switch)
Definition at line 241 of file drv_pwm_output.h.
Referenced by do_esc_calibration(), PX4IO::ioctl(), PX4FMU::pwm_ioctl(), and px4io_main().
#define PWM_SERVO_SET_MAX_PWM _PX4_IOC(_PWM_SERVO_BASE, 18) |
set the maximum PWM value the output will send
Definition at line 210 of file drv_pwm_output.h.
Referenced by VtolType::apply_pwm_limits(), PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_SET_MIN_PWM _PX4_IOC(_PWM_SERVO_BASE, 16) |
set the minimum PWM value the output will send
Definition at line 204 of file drv_pwm_output.h.
Referenced by VtolType::apply_pwm_limits(), PWMSim::ioctl(), PX4IO::ioctl(), motor_ramp_thread_main(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), pwm_main(), and set_min_pwm().
#define PWM_SERVO_SET_MODE _PX4_IOC(_PWM_SERVO_BASE, 34) |
Definition at line 269 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), motor_ramp_thread_main(), PX4FMU::pwm_ioctl(), DShotOutput::pwm_ioctl(), pwm_main(), CameraCapture::set_capture_control(), and PX4FMU::test().
#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _PX4_IOC(_PWM_SERVO_BASE, 32) |
setup OVERRIDE_IMMEDIATE behaviour on FMU fail
Definition at line 244 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl().
#define PWM_SERVO_SET_SBUS_RATE _PX4_IOC(_PWM_SERVO_BASE, 33) |
set SBUS output frame rate in Hz
Definition at line 247 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl().
#define PWM_SERVO_SET_SELECT_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 6) |
selects servo update rates, one bit per servo.
0 = default (50Hz), 1 = alternate
Definition at line 174 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
#define PWM_SERVO_SET_TERMINATION_FAILSAFE _PX4_IOC(_PWM_SERVO_BASE, 27) |
make failsafe non-recoverable (termination) if it occurs
Definition at line 238 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), and pwm_main().
#define PWM_SERVO_SET_TRIM_PWM _PX4_IOC(_PWM_SERVO_BASE, 20) |
set the TRIM value the output will send
Definition at line 216 of file drv_pwm_output.h.
Referenced by PX4IO::ioctl(), and PX4FMU::pwm_ioctl().
#define PWM_SERVO_SET_UPDATE_RATE _PX4_IOC(_PWM_SERVO_BASE, 3) |
set alternate servo update rate
Definition at line 165 of file drv_pwm_output.h.
Referenced by PWMSim::ioctl(), PX4IO::ioctl(), MK::pwm_ioctl(), PX4FMU::pwm_ioctl(), and pwm_main().
typedef uint16_t servo_position_t |
Servo output signal type, value is actual servo output pulse width in microseconds.
Definition at line 129 of file drv_pwm_output.h.
enum dshot_command_t |
Definition at line 303 of file drv_pwm_output.h.
__EXPORT int up_dshot_arm | ( | bool | armed | ) |
Arm or disarm dshot outputs (This will enable/disable complete timer for safety purpose.).
When disarmed, dshot output no pulse.
armed | If true, outputs are armed; if false they are disarmed. |
Referenced by DShotOutput::update_dshot_out_state(), and DShotOutput::~DShotOutput().
__EXPORT int up_dshot_init | ( | uint32_t | channel_mask, |
unsigned | dshot_pwm_freq | ||
) |
Intialise the Dshot outputs using the specified configuration.
channel_mask | Bitmask of channels (LSB = channel 0) to enable. This allows some of the channels to remain configured as GPIOs or as another function. |
dshot_pwm_freq | is frequency of DSHOT signal. Usually DSHOT1200, DSHOT600, DSHOT300 or DSHOT150 |
Referenced by DShotOutput::update_dshot_out_state().
__EXPORT void up_dshot_motor_command | ( | unsigned | channel, |
uint16_t | command, | ||
bool | telemetry | ||
) |
Send DShot command to a channel (motor).
channel | The channel to set. |
command | dshot_command_t |
telemetry | If true, request telemetry from that motor |
Referenced by DShotOutput::updateOutputs().
__EXPORT void up_dshot_motor_data_set | ( | unsigned | channel, |
uint16_t | throttle, | ||
bool | telemetry | ||
) |
Set the current dshot throttle value for a channel (motor).
channel | The channel to set. |
throttle | The output dshot throttle value in [0, 1999 = DSHOT_MAX_THROTTLE]. |
telemetry | If true, request telemetry from that motor |
Referenced by DShotOutput::updateOutputs().
__EXPORT void up_dshot_trigger | ( | void | ) |
Trigger dshot data transfer.
Referenced by DShotOutput::updateOutputs().
__EXPORT void up_pwm_servo_arm | ( | bool | armed | ) |
Arm or disarm servo outputs.
When disarmed, servos output no pulse.
armed | If true, outputs are armed; if false they are disarmed. |
Referenced by mixer_tick(), and PX4FMU::update_pwm_out_state().
__EXPORT void up_pwm_servo_deinit | ( | void | ) |
De-initialise the PWM servo outputs.
Referenced by PX4FMU::set_mode(), MK::task_main(), and PX4FMU::~PX4FMU().
__EXPORT servo_position_t up_pwm_servo_get | ( | unsigned | channel | ) |
Get the current output value for a channel.
channel | The channel to read. |
Referenced by PX4FMU::pwm_ioctl().
__EXPORT uint32_t up_pwm_servo_get_rate_group | ( | unsigned | group | ) |
Get a bitmap of output channels assigned to a given rate group.
group | The rate group to query. Rate groups are assigned contiguously starting from zero. |
Referenced by pwm_configure_rates(), PX4FMU::pwm_ioctl(), registers_get(), and PX4FMU::set_pwm_rate().
__EXPORT int up_pwm_servo_init | ( | uint32_t | channel_mask | ) |
Intialise the PWM servo outputs using the specified configuration.
channel_mask | Bitmask of channels (LSB = channel 0) to enable. This allows some of the channels to remain configured as GPIOs or as another function. |
Referenced by PX4FMU::update_pwm_out_state(), and user_start().
__EXPORT int up_pwm_servo_set | ( | unsigned | channel, |
servo_position_t | value | ||
) |
Set the current output value for a channel.
channel | The channel to set. |
value | The output pulse width in microseconds. |
Referenced by mixer_tick(), PX4FMU::pwm_ioctl(), and PX4FMU::updateOutputs().
__EXPORT int up_pwm_servo_set_rate | ( | unsigned | rate | ) |
Set the servo update rate for all rate groups.
rate | The update rate in Hz to set. |
Referenced by MK::task_main().
__EXPORT int up_pwm_servo_set_rate_group_update | ( | unsigned | group, |
unsigned | rate | ||
) |
Set the update rate for a given rate group.
group | The rate group whose update rate will be changed. |
rate | The update rate in Hz. |
Referenced by pwm_configure_rates(), and PX4FMU::set_pwm_rate().
__EXPORT void up_pwm_update | ( | void | ) |
Trigger all timer's channels in Oneshot mode to fire the oneshot with updated values.
Nothing is done if not in oneshot mode.
Referenced by mixer_tick(), pwm_main(), registers_set(), and PX4FMU::updateOutputs().