|
PX4 Firmware
PX4 Autopilot Software http://px4.io
|
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 |
Definition at line 121 of file mkblctrl.cpp.
| enum MK::FrameType |
| Enumerator | |
|---|---|
| FRAME_PLUS | |
| FRAME_X | |
Definition at line 129 of file mkblctrl.cpp.
| enum MK::MappingMode |
| Enumerator | |
|---|---|
| MAPPING_MK | |
| MAPPING_PX4 | |
Definition at line 124 of file mkblctrl.cpp.
| MK::MK | ( | int | bus, |
| const char * | _device_path | ||
| ) |
Definition at line 220 of file mkblctrl.cpp.
References _device.
| MK::~MK | ( | ) |
Definition at line 247 of file mkblctrl.cpp.
References _device, _primary_pwm_device, _task, _task_should_exit, and unregister_driver().
|
staticprivate |
Definition at line 946 of file mkblctrl.cpp.
References actuator_controls_s::control.
Referenced by pwm_ioctl().
|
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.
|
virtual |
Definition at line 958 of file mkblctrl.cpp.
References pwm_ioctl().
| unsigned int MK::mk_check_for_blctrl | ( | unsigned int | count, |
| bool | showOutput, | ||
| bool | initI2C | ||
| ) |
Definition at line 668 of file mkblctrl.cpp.
References _overrideSecurityChecks, _task_should_exit, BLCTRL_BASE_ADDR, BLCTRL_NEW, BLCTRL_OLD, MotorData_t::Current, ToneAlarmInterface::init(), MAX_MOTORS, MotorData_t::MaxPWM, Motor, MOTOR_STATE_PRESENT_MASK, msg, OK, MotorData_t::RawPwmValue, MotorData_t::ReadMode, MotorData_t::RoundCount, MotorData_t::SetPoint, MotorData_t::SetPointLowerBits, MotorData_t::State, MotorData_t::Temperature, and MotorData_t::Version.
|
private |
Definition at line 660 of file mkblctrl.cpp.
References _armed, and status.
Referenced by pwm_ioctl(), and task_main().
|
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().
|
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().
|
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().
|
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().
|
private |
Definition at line 973 of file mkblctrl.cpp.
References _controls, _max_actuators, _mixers, _num_outputs, _rc_max_value, _rc_min_value, _update_rate, pwm_output_values::channel_count, control_callback(), DEVICE_DEBUG, MixerGroup::load_from_buf(), MicroBenchHRT::lock(), MIXERIOCLOADBUF, MIXERIOCRESET, mk_servo_arm(), mk_servo_set(), Motor, OK, PWM_SERVO_ARM, PWM_SERVO_CLEAR_ARM_OK, PWM_SERVO_DISARM, PWM_SERVO_GET, PWM_SERVO_GET_COUNT, PWM_SERVO_GET_MAX_PWM, PWM_SERVO_GET_MIN_PWM, PWM_SERVO_GET_RATEGROUP, PWM_SERVO_GET_UPDATE_RATE, PWM_SERVO_SET, PWM_SERVO_SET_ARM_OK, PWM_SERVO_SET_MAX_PWM, PWM_SERVO_SET_MIN_PWM, PWM_SERVO_SET_SELECT_UPDATE_RATE, PWM_SERVO_SET_UPDATE_RATE, MotorData_t::RawPwmValue, scaling(), set_rc_max_value(), set_rc_min_value(), MicroBenchHRT::unlock(), and pwm_output_values::values.
Referenced by ioctl().
|
private |
Definition at line 432 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), task_main(), and write().
| void MK::set_frametype | ( | int | frametype | ) |
Definition at line 335 of file mkblctrl.cpp.
References _frametype.
| int MK::set_motor_count | ( | unsigned | count | ) |
Definition at line 355 of file mkblctrl.cpp.
References _frametype, _num_outputs, _px4mode, addrTranslator, blctrlAddr_hexa_plus, blctrlAddr_hexa_x, blctrlAddr_octo_plus, blctrlAddr_octo_x, blctrlAddr_px4, blctrlAddr_quad_plus, blctrlAddr_quad_x, FRAME_PLUS, FRAME_X, MAPPING_MK, and OK.
| int MK::set_motor_test | ( | bool | motortest | ) |
Definition at line 418 of file mkblctrl.cpp.
References _motortest, and OK.
| int MK::set_overrideSecurityChecks | ( | bool | overrideSecurityChecks | ) |
Definition at line 425 of file mkblctrl.cpp.
References _overrideSecurityChecks, and OK.
| void MK::set_px4mode | ( | int | px4mode | ) |
Definition at line 329 of file mkblctrl.cpp.
References _px4mode.
| void MK::set_rc_max_value | ( | unsigned | value | ) |
Definition at line 348 of file mkblctrl.cpp.
References _rc_max_value.
Referenced by pwm_ioctl().
| void MK::set_rc_min_value | ( | unsigned | value | ) |
Definition at line 341 of file mkblctrl.cpp.
References _rc_min_value.
Referenced by pwm_ioctl().
|
private |
Definition at line 462 of file mkblctrl.cpp.
References _controls, _indicate_esc, _mixers, _motortest, _num_outputs, _overrideSecurityChecks, _param_indicate_esc, _t_actuator_armed, _t_actuators, _t_esc_status, _t_outputs, _task, _task_should_exit, _tune_control_sub, _update_rate, actuator_armed_s::armed, BLCTRL_BASE_ADDR, BLCTRL_MIN_VALUE, CONTROL_INPUT_DROP_LIMIT_MS, esc_status_s::counter, MotorData_t::Current, DEVICE_LOG, esc_status_s::esc, uart_esc::esc, esc_report_s::esc_address, esc_status_s::esc_connectiontype, esc_status_s::esc_count, esc_report_s::esc_current, esc_report_s::esc_errorcount, esc_report_s::esc_rpm, esc_report_s::esc_state, esc_report_s::esc_temperature, ESC_UORB_PUBLISH_DELAY, esc_report_s::esc_voltage, hrt_absolute_time(), actuator_armed_s::lockdown, MixerGroup::mix(), mk_servo_arm(), mk_servo_locate(), mk_servo_set(), mk_servo_test(), Motor, actuator_outputs_s::noutputs, orb_advertise(), orb_advertise_multi(), orb_advertise_queue(), orb_check(), orb_copy(), ORB_ID, ORB_ID_VEHICLE_ATTITUDE_CONTROLS, ORB_PRIO_HIGH, orb_publish(), orb_set_interval(), orb_subscribe(), actuator_outputs_s::output, param_get(), scaling(), MotorData_t::SetPoint_PX4, MotorData_t::Temperature, actuator_outputs_s::timestamp, esc_status_s::timestamp, tune_control, up_pwm_servo_deinit(), and up_pwm_servo_set_rate().
|
staticprivate |
Definition at line 323 of file mkblctrl.cpp.
Referenced by init().
|
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.
|
private |
Definition at line 170 of file mkblctrl.cpp.
Referenced by mk_servo_arm(), and mk_servo_set().
|
private |
Definition at line 177 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), and task_main().
|
private |
Definition at line 161 of file mkblctrl.cpp.
|
private |
Definition at line 160 of file mkblctrl.cpp.
Referenced by set_frametype(), and set_motor_count().
|
private |
Definition at line 173 of file mkblctrl.cpp.
Referenced by task_main().
|
staticprivate |
Definition at line 151 of file mkblctrl.cpp.
Referenced by pwm_ioctl().
|
private |
Definition at line 172 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), and task_main().
|
private |
Definition at line 158 of file mkblctrl.cpp.
Referenced by mk_servo_test().
|
private |
Definition at line 167 of file mkblctrl.cpp.
Referenced by mk_servo_test(), set_motor_test(), and task_main().
|
private |
Definition at line 165 of file mkblctrl.cpp.
Referenced by init(), mk_servo_locate(), mk_servo_set(), mk_servo_test(), pwm_ioctl(), set_motor_count(), task_main(), and write().
|
private |
Definition at line 168 of file mkblctrl.cpp.
Referenced by mk_check_for_blctrl(), set_overrideSecurityChecks(), and task_main().
|
private |
Definition at line 176 of file mkblctrl.cpp.
Referenced by init(), and task_main().
|
private |
Definition at line 166 of file mkblctrl.cpp.
|
private |
Definition at line 159 of file mkblctrl.cpp.
Referenced by set_motor_count(), and set_px4mode().
|
private |
Definition at line 175 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), set_rc_max_value(), and write().
|
private |
Definition at line 174 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), set_rc_min_value(), and write().
|
private |
Definition at line 157 of file mkblctrl.cpp.
Referenced by task_main().
|
private |
Definition at line 156 of file mkblctrl.cpp.
Referenced by task_main().
|
private |
Definition at line 163 of file mkblctrl.cpp.
Referenced by task_main().
|
private |
Definition at line 162 of file mkblctrl.cpp.
Referenced by task_main().
|
private |
Definition at line 155 of file mkblctrl.cpp.
Referenced by init(), task_main(), and ~MK().
|
private |
Definition at line 169 of file mkblctrl.cpp.
Referenced by mk_check_for_blctrl(), task_main(), and ~MK().
|
private |
Definition at line 164 of file mkblctrl.cpp.
Referenced by play_beep(), and task_main().
|
private |
Definition at line 154 of file mkblctrl.cpp.
Referenced by pwm_ioctl(), and task_main().
|
private |
Definition at line 171 of file mkblctrl.cpp.
Referenced by init(), mk_servo_set(), and mk_servo_test().
|
private |
Definition at line 178 of file mkblctrl.cpp.
Referenced by mk_check_for_blctrl(), mk_servo_set(), mk_servo_test(), pwm_ioctl(), task_main(), and write().
|
staticprivate |
Definition at line 152 of file mkblctrl.cpp.
Referenced by mk_servo_set().