PX4 Firmware
PX4 Autopilot Software http://px4.io
PWMSim Class Reference

#include <PWMSim.hpp>

Inheritance diagram for PWMSim:
Collaboration diagram for PWMSim:

Public Member Functions

 PWMSim (bool hil_mode_enabled)
 
int print_status () override
 
void Run () override
 
int ioctl (device::file_t *filp, int cmd, unsigned long arg) override
 Perform an ioctl operation on the device. More...
 
bool updateOutputs (bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs, unsigned num_control_groups_updated) override
 Callback to update the (physical) actuator outputs in the driver. More...
 
- Public Member Functions inherited from cdev::CDev
 CDev (const char *devname)
 Constructor. More...
 
 CDev (const CDev &)=delete
 
CDevoperator= (const CDev &)=delete
 
 CDev (CDev &&)=delete
 
CDevoperator= (CDev &&)=delete
 
virtual ~CDev ()
 
virtual int init ()
 
virtual int open (file_t *filep)
 Handle an open of the device. More...
 
virtual int close (file_t *filep)
 Handle a close of the device. More...
 
virtual ssize_t read (file_t *filep, char *buffer, size_t buflen)
 Perform a read from the device. More...
 
virtual ssize_t write (file_t *filep, const char *buffer, size_t buflen)
 Perform a write to the device. More...
 
virtual off_t seek (file_t *filep, off_t offset, int whence)
 Perform a logical seek operation on the device. More...
 
virtual int poll (file_t *filep, px4_pollfd_struct_t *fds, bool setup)
 Perform a poll setup/teardown operation. More...
 
const char * get_devname () const
 Get the device name. More...
 
- Public Member Functions inherited from OutputModuleInterface
 OutputModuleInterface (const char *name, const px4::wq_config_t &config)
 
virtual void mixerChanged ()
 called whenever the mixer gets updated/reset More...
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 

Private Attributes

MixingOutput _mixing_output {MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false}
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 

Static Private Attributes

static constexpr uint16_t PWM_SIM_DISARMED_MAGIC = 900
 
static constexpr uint16_t PWM_SIM_FAILSAFE_MAGIC = 600
 
static constexpr uint16_t PWM_SIM_PWM_MIN_MAGIC = 1000
 
static constexpr uint16_t PWM_SIM_PWM_MAX_MAGIC = 2000
 

Additional Inherited Members

- Static Public Attributes inherited from OutputModuleInterface
static constexpr int MAX_ACTUATORS = PWM_OUTPUT_MAX_CHANNELS
 
- Protected Member Functions inherited from cdev::CDev
virtual pollevent_t poll_state (file_t *filep)
 Check the current state of the device for poll events from the perspective of the file. More...
 
virtual void poll_notify (pollevent_t events)
 Report new poll events. More...
 
virtual void poll_notify_one (px4_pollfd_struct_t *fds, pollevent_t events)
 Internal implementation of poll_notify. More...
 
virtual int open_first (file_t *filep)
 Notification of the first open. More...
 
virtual int close_last (file_t *filep)
 Notification of the last close. More...
 
virtual int register_class_devname (const char *class_devname)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
virtual int unregister_class_devname (const char *class_devname, unsigned class_instance)
 Register a class device name, automatically adding device class instance suffix if need be. More...
 
void lock ()
 Take the driver lock. More...
 
void unlock ()
 Release the driver lock. More...
 
int unregister_driver_and_memory ()
 First, unregisters the driver. More...
 
- Protected Attributes inherited from cdev::CDev
px4_sem_t _lock
 lock to protect access to all class members (also for derived classes) More...
 
- Static Protected Attributes inherited from cdev::CDev
static const px4_file_operations_t fops = {}
 Pointer to the default cdev file operations table; useful for registering clone devices etc. More...
 

Detailed Description

Definition at line 47 of file PWMSim.hpp.

Constructor & Destructor Documentation

◆ PWMSim()

PWMSim::PWMSim ( bool  hil_mode_enabled)

Definition at line 42 of file PWMSim.cpp.

References _mixing_output, ToneAlarmInterface::init(), PWM_SIM_DISARMED_MAGIC, PWM_SIM_FAILSAFE_MAGIC, PWM_SIM_PWM_MAX_MAGIC, PWM_SIM_PWM_MIN_MAGIC, MixingOutput::setAllDisarmedValues(), MixingOutput::setAllFailsafeValues(), MixingOutput::setAllMaxValues(), MixingOutput::setAllMinValues(), and MixingOutput::setIgnoreLockdown().

Referenced by task_spawn().

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

Member Function Documentation

◆ custom_command()

int PWMSim::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 268 of file PWMSim.cpp.

References print_usage().

Here is the call graph for this function:

◆ ioctl()

int PWMSim::ioctl ( device::file_t filep,
int  cmd,
unsigned long  arg 
)
overridevirtual

Perform an ioctl operation on the device.

The default implementation handles DIOC_GETPRIV, and otherwise returns -ENOTTY. Subclasses should call the default implementation for any command they do not handle themselves.

Parameters
filepPointer to the NuttX file structure.
cmdThe ioctl command value.
argThe ioctl argument value.
Returns
OK on success, or -errno otherwise.

Reimplemented from cdev::CDev.

Definition at line 90 of file PWMSim.cpp.

References _mixing_output, pwm_output_values::channel_count, MixingOutput::disarmedValue(), MixingOutput::failsafeValue(), MixingOutput::loadMixerThreadSafe(), cdev::CDev::lock(), OutputModuleInterface::MAX_ACTUATORS, MixingOutput::maxValue(), MixingOutput::minValue(), MIXERIOCLOADBUF, MIXERIOCRESET, OK, PWM_OUTPUT_MAX_CHANNELS, PWM_SERVO_ARM, PWM_SERVO_DISARM, PWM_SERVO_GET_COUNT, PWM_SERVO_GET_DEFAULT_UPDATE_RATE, PWM_SERVO_GET_DISARMED_PWM, PWM_SERVO_GET_FAILSAFE_PWM, PWM_SERVO_GET_MAX_PWM, PWM_SERVO_GET_MIN_PWM, PWM_SERVO_GET_RATEGROUP, PWM_SERVO_GET_SELECT_UPDATE_RATE, PWM_SERVO_GET_TRIM_PWM, PWM_SERVO_GET_UPDATE_RATE, PWM_SERVO_SET_MAX_PWM, PWM_SERVO_SET_MIN_PWM, PWM_SERVO_SET_SELECT_UPDATE_RATE, PWM_SERVO_SET_UPDATE_RATE, MixingOutput::resetMixerThreadSafe(), cdev::CDev::unlock(), and pwm_output_values::values.

Here is the call graph for this function:

◆ print_status()

int PWMSim::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 273 of file PWMSim.cpp.

References _mixing_output, and MixingOutput::printStatus().

Here is the call graph for this function:

◆ print_usage()

int PWMSim::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 279 of file PWMSim.cpp.

Referenced by custom_command(), and task_spawn().

Here is the caller graph for this function:

◆ Run()

void PWMSim::Run ( )
override

Definition at line 57 of file PWMSim.cpp.

References _mixing_output, _parameter_update_sub, uORB::Subscription::copy(), MixingOutput::unregister(), MixingOutput::update(), uORB::Subscription::updated(), and MixingOutput::updateSubscriptions().

Here is the call graph for this function:

◆ task_spawn()

int PWMSim::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 236 of file PWMSim.cpp.

References ll40ls::instance, print_usage(), and PWMSim().

Here is the call graph for this function:

◆ updateOutputs()

bool PWMSim::updateOutputs ( bool  stop_motors,
uint16_t  outputs[MAX_ACTUATORS],
unsigned  num_outputs,
unsigned  num_control_groups_updated 
)
overridevirtual

Callback to update the (physical) actuator outputs in the driver.

Parameters
stop_motorsif true, all motors must be stopped (if false, individual motors might still be stopped via outputs[i] == disarmed_value)
outputsindividual actuator outputs in range [min, max] or failsafe/disarmed value
num_outputsnumber of outputs (<= max_num_outputs)
num_control_groups_updatednumber of actuator_control groups updated
Returns
if true, the update got handled, and actuator_outputs can be published

Implements OutputModuleInterface.

Definition at line 81 of file PWMSim.cpp.

Member Data Documentation

◆ _mixing_output

MixingOutput PWMSim::_mixing_output {MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false}
private

Definition at line 77 of file PWMSim.hpp.

Referenced by ioctl(), print_status(), PWMSim(), and Run().

◆ _parameter_update_sub

uORB::Subscription PWMSim::_parameter_update_sub {ORB_ID(parameter_update)}
private

Definition at line 78 of file PWMSim.hpp.

Referenced by Run().

◆ PWM_SIM_DISARMED_MAGIC

constexpr uint16_t PWMSim::PWM_SIM_DISARMED_MAGIC = 900
staticprivate

Definition at line 72 of file PWMSim.hpp.

Referenced by PWMSim().

◆ PWM_SIM_FAILSAFE_MAGIC

constexpr uint16_t PWMSim::PWM_SIM_FAILSAFE_MAGIC = 600
staticprivate

Definition at line 73 of file PWMSim.hpp.

Referenced by PWMSim().

◆ PWM_SIM_PWM_MAX_MAGIC

constexpr uint16_t PWMSim::PWM_SIM_PWM_MAX_MAGIC = 2000
staticprivate

Definition at line 75 of file PWMSim.hpp.

Referenced by PWMSim().

◆ PWM_SIM_PWM_MIN_MAGIC

constexpr uint16_t PWMSim::PWM_SIM_PWM_MIN_MAGIC = 1000
staticprivate

Definition at line 74 of file PWMSim.hpp.

Referenced by PWMSim().


The documentation for this class was generated from the following files: