PX4 Firmware
PX4 Autopilot Software http://px4.io
snapdragon_pwm_out.cpp File Reference
#include <stdint.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/posix.h>
#include <errno.h>
#include <math.h>
#include <string.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_mixer.h>
#include <lib/mixer/MultirotorMixer/MultirotorMixer.hpp>
#include <lib/mixer/MixerGroup.hpp>
#include <lib/mixer/mixer_load.h>
#include <lib/parameters/param.h>
#include <lib/perf/perf_counter.h>
#include <lib/output_limit/output_limit.h>
#include <dev_fs_lib_pwm.h>
Include dependency graph for snapdragon_pwm_out.cpp:

Go to the source code of this file.

Namespaces

 snapdragon_pwm
 

Functions

static void snapdragon_pwm::usage ()
 
static void snapdragon_pwm::start ()
 
static void snapdragon_pwm::stop ()
 
static int snapdragon_pwm::pwm_initialize (const char *device)
 
static void snapdragon_pwm::pwm_deinitialize ()
 
static void snapdragon_pwm::send_outputs_pwm (const uint16_t *pwm)
 
static void snapdragon_pwm::task_main_trampoline (int argc, char *argv[])
 
static void snapdragon_pwm::subscribe ()
 
static void snapdragon_pwm::task_main (int argc, char *argv[])
 
static void snapdragon_pwm::update_params (Mixer::Airmode &airmode)
 
int snapdragon_pwm::initialize_mixer (const char *mixer_filename)
 
int snapdragon_pwm::mixer_control_callback (uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
 
__EXPORT int snapdragon_pwm_out_main (int argc, char *argv[])
 

Variables

static px4_task_t snapdragon_pwm::_task_handle = -1
 
volatile bool snapdragon_pwm::_task_should_exit = false
 
static bool snapdragon_pwm::_is_running = false
 
static const int snapdragon_pwm::NUM_PWM = 4
 
static char snapdragon_pwm::_device [] = "/dev/pwm-1"
 
static const int snapdragon_pwm::PIN_GPIO = 27
 
static struct ::dspal_pwm_ioctl_signal_definition snapdragon_pwm::_signal_definition
 
static struct ::dspal_pwm snapdragon_pwm::_pwm_gpio [NUM_PWM]
 
static struct ::dspal_pwm_ioctl_update_buffer * snapdragon_pwm::_update_buffer
 
static struct ::dspal_pwm * snapdragon_pwm::_pwm
 
static const int snapdragon_pwm::FREQUENCY_PWM_HZ = 400
 
static char snapdragon_pwm::_mixer_filename [32] = "/dev/fs/quad_x.main.mix"
 
int snapdragon_pwm::_controls_subs [actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
 
int snapdragon_pwm::_armed_sub
 
int snapdragon_pwm::_fd = -1
 
orb_advert_t snapdragon_pwm::_outputs_pub = nullptr
 
actuator_controls_s snapdragon_pwm::_controls [actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
 
orb_id_t snapdragon_pwm::_controls_topics [actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
 
actuator_outputs_s snapdragon_pwm::_outputs
 
actuator_armed_s snapdragon_pwm::_armed
 
uint8_t snapdragon_pwm::_poll_fds_num = 0
 
px4_pollfd_struct_t snapdragon_pwm::_poll_fds [actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS]
 
uint32_t snapdragon_pwm::_groups_required = 0
 
output_limit_t snapdragon_pwm::_pwm_limit
 
int32_t snapdragon_pwm::_pwm_disarmed
 
int32_t snapdragon_pwm::_pwm_min
 
int32_t snapdragon_pwm::_pwm_max
 
MultirotorMixersnapdragon_pwm::_mixer = nullptr
 
perf_counter_t snapdragon_pwm::_perf_control_latency = nullptr
 

Function Documentation

◆ snapdragon_pwm_out_main()

int snapdragon_pwm_out_main ( int  argc,
char *  argv[] 
)

Definition at line 530 of file snapdragon_pwm_out.cpp.

References snapdragon_pwm::_device, snapdragon_pwm::_is_running, snapdragon_pwm::_mixer_filename, snapdragon_pwm::_pwm_disarmed, snapdragon_pwm::_pwm_max, snapdragon_pwm::_pwm_min, param_find(), param_get(), snapdragon_pwm::start(), snapdragon_pwm::stop(), and snapdragon_pwm::usage().

Referenced by snapdragon_pwm::usage().

Here is the call graph for this function:
Here is the caller graph for this function: