PX4 Firmware
PX4 Autopilot Software http://px4.io
MK Class Reference
Inheritance diagram for MK:
Collaboration diagram for MK:

Public Types

enum  MappingMode { MAPPING_MK = 0, MAPPING_PX4 }
 
enum  FrameType { FRAME_PLUS = 0, FRAME_X }
 

Public Member Functions

 MK (int bus, const char *_device_path)
 
 ~MK ()
 
virtual int ioctl (file *filp, int cmd, unsigned long arg)
 
virtual int init (unsigned motors)
 
virtual ssize_t write (file *filp, const char *buffer, size_t len)
 
int set_motor_count (unsigned count)
 
int set_motor_test (bool motortest)
 
int set_overrideSecurityChecks (bool overrideSecurityChecks)
 
void set_px4mode (int px4mode)
 
void set_frametype (int frametype)
 
unsigned int mk_check_for_blctrl (unsigned int count, bool showOutput, bool initI2C)
 
void set_rc_min_value (unsigned value)
 
void set_rc_max_value (unsigned value)
 

Private Member Functions

int task_main ()
 
int pwm_ioctl (file *filp, int cmd, unsigned long arg)
 
int mk_servo_arm (bool status)
 
int mk_servo_set (unsigned int chan, short val)
 
int mk_servo_test (unsigned int chan)
 
int mk_servo_locate ()
 
short scaling (float val, float inMin, float inMax, float outMin, float outMax)
 
void play_beep (int count)
 

Static Private Member Functions

static int task_main_trampoline (int argc, char *argv[])
 
static int control_callback (uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
 

Private Attributes

int _update_rate
 
int _task
 
int _t_actuators
 
int _t_actuator_armed
 
unsigned int _motor
 
int _px4mode
 
int _frametype
 
char _device [20]
 
orb_advert_t _t_outputs
 
orb_advert_t _t_esc_status
 
orb_advert_t _tune_control_sub
 
unsigned int _num_outputs
 
bool _primary_pwm_device
 
bool _motortest
 
bool _overrideSecurityChecks
 
volatile bool _task_should_exit
 
bool _armed
 
unsigned long debugCounter
 
MixerGroup_mixers
 
bool _indicate_esc
 
unsigned _rc_min_value
 
unsigned _rc_max_value
 
param_t _param_indicate_esc
 
actuator_controls_s _controls
 
MotorData_t Motor [MAX_MOTORS]
 

Static Private Attributes

static const unsigned _max_actuators = MAX_MOTORS
 
static const bool showDebug = false
 

Detailed Description

Definition at line 121 of file mkblctrl.cpp.

Member Enumeration Documentation

◆ FrameType

Enumerator
FRAME_PLUS 
FRAME_X 

Definition at line 129 of file mkblctrl.cpp.

◆ MappingMode

Enumerator
MAPPING_MK 
MAPPING_PX4 

Definition at line 124 of file mkblctrl.cpp.

Constructor & Destructor Documentation

◆ MK()

MK::MK ( int  bus,
const char *  _device_path 
)

Definition at line 220 of file mkblctrl.cpp.

References _device.

◆ ~MK()

MK::~MK ( )

Definition at line 247 of file mkblctrl.cpp.

References _device, _primary_pwm_device, _task, _task_should_exit, and unregister_driver().

Here is the call graph for this function:

Member Function Documentation

◆ control_callback()

int MK::control_callback ( uintptr_t  handle,
uint8_t  control_group,
uint8_t  control_index,
float &  input 
)
staticprivate

Definition at line 946 of file mkblctrl.cpp.

References actuator_controls_s::control.

Referenced by pwm_ioctl().

Here is the caller graph for this function:

◆ init()

int MK::init ( unsigned  motors)
virtual

Definition at line 277 of file mkblctrl.cpp.

References _device, _num_outputs, _param_indicate_esc, _primary_pwm_device, _task, debugCounter, DEVICE_DEBUG, DEVICE_LOG, ToneAlarmInterface::init(), OK, param_find(), register_driver(), task_main_trampoline(), and warnx.

Here is the call graph for this function:

◆ ioctl()

int MK::ioctl ( file filp,
int  cmd,
unsigned long  arg 
)
virtual

Definition at line 958 of file mkblctrl.cpp.

References pwm_ioctl().

Here is the call graph for this function:

◆ mk_check_for_blctrl()

unsigned int MK::mk_check_for_blctrl ( unsigned int  count,
bool  showOutput,
bool  initI2C 
)

◆ mk_servo_arm()

int MK::mk_servo_arm ( bool  status)
private

Definition at line 660 of file mkblctrl.cpp.

References _armed, and status.

Referenced by pwm_ioctl(), and task_main().

Here is the caller graph for this function:

◆ mk_servo_locate()

int MK::mk_servo_locate ( )
private

Definition at line 913 of file mkblctrl.cpp.

References _num_outputs, addrTranslator, BLCTRL_BASE_ADDR, hrt_absolute_time(), MOTOR_LOCATE_DELAY, msg, and play_beep().

Referenced by task_main().

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

◆ mk_servo_set()

int MK::mk_servo_set ( unsigned int  chan,
short  val 
)
private

Definition at line 736 of file mkblctrl.cpp.

References _armed, _num_outputs, addrTranslator, BLCTRL_BASE_ADDR, BLCTRL_OLD, MotorData_t::Current, debugCounter, MotorData_t::MaxPWM, Motor, MOTOR_STATE_ERROR_MASK, MOTOR_STATE_PRESENT_MASK, msg, OK, MotorData_t::RoundCount, MotorData_t::SetPoint, MotorData_t::SetPointLowerBits, showDebug, MotorData_t::State, and MotorData_t::Temperature.

Referenced by pwm_ioctl(), task_main(), and write().

Here is the caller graph for this function:

◆ mk_servo_test()

int MK::mk_servo_test ( unsigned int  chan)
private

Definition at line 846 of file mkblctrl.cpp.

References _motor, _motortest, _num_outputs, addrTranslator, BLCTRL_BASE_ADDR, BLCTRL_MIN_VALUE, BLCTRL_OLD, debugCounter, Motor, MOTOR_SPINUP_COUNTER, msg, MotorData_t::SetPoint, and MotorData_t::SetPointLowerBits.

Referenced by task_main().

Here is the caller graph for this function:

◆ play_beep()

void MK::play_beep ( int  count)
private

Definition at line 449 of file mkblctrl.cpp.

References _tune_control_sub, ORB_ID, orb_publish(), tune_control, and tune_control_s::tune_id.

Referenced by mk_servo_locate().

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

◆ pwm_ioctl()

int MK::pwm_ioctl ( file filp,
int  cmd,
unsigned long  arg 
)
private

◆ scaling()

short MK::scaling ( float  val,
float  inMin,
float  inMax,
float  outMin,
float  outMax 
)
private

Definition at line 432 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), task_main(), and write().

Here is the caller graph for this function:

◆ set_frametype()

void MK::set_frametype ( int  frametype)

Definition at line 335 of file mkblctrl.cpp.

References _frametype.

◆ set_motor_count()

◆ set_motor_test()

int MK::set_motor_test ( bool  motortest)

Definition at line 418 of file mkblctrl.cpp.

References _motortest, and OK.

◆ set_overrideSecurityChecks()

int MK::set_overrideSecurityChecks ( bool  overrideSecurityChecks)

Definition at line 425 of file mkblctrl.cpp.

References _overrideSecurityChecks, and OK.

◆ set_px4mode()

void MK::set_px4mode ( int  px4mode)

Definition at line 329 of file mkblctrl.cpp.

References _px4mode.

◆ set_rc_max_value()

void MK::set_rc_max_value ( unsigned  value)

Definition at line 348 of file mkblctrl.cpp.

References _rc_max_value.

Referenced by pwm_ioctl().

Here is the caller graph for this function:

◆ set_rc_min_value()

void MK::set_rc_min_value ( unsigned  value)

Definition at line 341 of file mkblctrl.cpp.

References _rc_min_value.

Referenced by pwm_ioctl().

Here is the caller graph for this function:

◆ task_main()

int MK::task_main ( )
private

◆ task_main_trampoline()

int MK::task_main_trampoline ( int  argc,
char *  argv[] 
)
staticprivate

Definition at line 323 of file mkblctrl.cpp.

Referenced by init().

Here is the caller graph for this function:

◆ write()

ssize_t MK::write ( file filp,
const char *  buffer,
size_t  len 
)
virtual

Definition at line 1120 of file mkblctrl.cpp.

References _num_outputs, _rc_max_value, _rc_min_value, mk_servo_set(), Motor, MotorData_t::RawPwmValue, scaling(), and pwm_output_values::values.

Here is the call graph for this function:

Member Data Documentation

◆ _armed

bool MK::_armed
private

Definition at line 170 of file mkblctrl.cpp.

Referenced by mk_servo_arm(), and mk_servo_set().

◆ _controls

actuator_controls_s MK::_controls
private

Definition at line 177 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), and task_main().

◆ _device

char MK::_device[20]
private

Definition at line 161 of file mkblctrl.cpp.

Referenced by init(), MK(), and ~MK().

◆ _frametype

int MK::_frametype
private

Definition at line 160 of file mkblctrl.cpp.

Referenced by set_frametype(), and set_motor_count().

◆ _indicate_esc

bool MK::_indicate_esc
private

Definition at line 173 of file mkblctrl.cpp.

Referenced by task_main().

◆ _max_actuators

const unsigned MK::_max_actuators = MAX_MOTORS
staticprivate

Definition at line 151 of file mkblctrl.cpp.

Referenced by pwm_ioctl().

◆ _mixers

MixerGroup* MK::_mixers
private

Definition at line 172 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), and task_main().

◆ _motor

unsigned int MK::_motor
private

Definition at line 158 of file mkblctrl.cpp.

Referenced by mk_servo_test().

◆ _motortest

bool MK::_motortest
private

Definition at line 167 of file mkblctrl.cpp.

Referenced by mk_servo_test(), set_motor_test(), and task_main().

◆ _num_outputs

unsigned int MK::_num_outputs
private

◆ _overrideSecurityChecks

bool MK::_overrideSecurityChecks
private

Definition at line 168 of file mkblctrl.cpp.

Referenced by mk_check_for_blctrl(), set_overrideSecurityChecks(), and task_main().

◆ _param_indicate_esc

param_t MK::_param_indicate_esc
private

Definition at line 176 of file mkblctrl.cpp.

Referenced by init(), and task_main().

◆ _primary_pwm_device

bool MK::_primary_pwm_device
private

Definition at line 166 of file mkblctrl.cpp.

Referenced by init(), and ~MK().

◆ _px4mode

int MK::_px4mode
private

Definition at line 159 of file mkblctrl.cpp.

Referenced by set_motor_count(), and set_px4mode().

◆ _rc_max_value

unsigned MK::_rc_max_value
private

Definition at line 175 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), set_rc_max_value(), and write().

◆ _rc_min_value

unsigned MK::_rc_min_value
private

Definition at line 174 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), set_rc_min_value(), and write().

◆ _t_actuator_armed

int MK::_t_actuator_armed
private

Definition at line 157 of file mkblctrl.cpp.

Referenced by task_main().

◆ _t_actuators

int MK::_t_actuators
private

Definition at line 156 of file mkblctrl.cpp.

Referenced by task_main().

◆ _t_esc_status

orb_advert_t MK::_t_esc_status
private

Definition at line 163 of file mkblctrl.cpp.

Referenced by task_main().

◆ _t_outputs

orb_advert_t MK::_t_outputs
private

Definition at line 162 of file mkblctrl.cpp.

Referenced by task_main().

◆ _task

int MK::_task
private

Definition at line 155 of file mkblctrl.cpp.

Referenced by init(), task_main(), and ~MK().

◆ _task_should_exit

volatile bool MK::_task_should_exit
private

Definition at line 169 of file mkblctrl.cpp.

Referenced by mk_check_for_blctrl(), task_main(), and ~MK().

◆ _tune_control_sub

orb_advert_t MK::_tune_control_sub
private

Definition at line 164 of file mkblctrl.cpp.

Referenced by play_beep(), and task_main().

◆ _update_rate

int MK::_update_rate
private

Definition at line 154 of file mkblctrl.cpp.

Referenced by pwm_ioctl(), and task_main().

◆ debugCounter

unsigned long MK::debugCounter
private

Definition at line 171 of file mkblctrl.cpp.

Referenced by init(), mk_servo_set(), and mk_servo_test().

◆ Motor

MotorData_t MK::Motor[MAX_MOTORS]
private

◆ showDebug

const bool MK::showDebug = false
staticprivate

Definition at line 152 of file mkblctrl.cpp.

Referenced by mk_servo_set().


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