PX4 Firmware
PX4 Autopilot Software http://px4.io
esc_calibration.cpp File Reference

Definition of esc calibration. More...

#include "esc_calibration.h"
#include "calibration_messages.h"
#include "calibration_routines.h"
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/time.h>
#include <systemlib/mavlink_log.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/battery_status.h>
Include dependency graph for esc_calibration.cpp:

Go to the source code of this file.

Functions

int do_esc_calibration (orb_advert_t *mavlink_log_pub, struct actuator_armed_s *armed)
 

Detailed Description

Definition of esc calibration.

Author
Roman Bapst roman.nosp@m.@px4.nosp@m..io

Definition in file esc_calibration.cpp.

Function Documentation

◆ do_esc_calibration()

int do_esc_calibration ( orb_advert_t mavlink_log_pub,
struct actuator_armed_s armed 
)

Definition at line 57 of file esc_calibration.cpp.

References CAL_QGC_DONE_MSG, CAL_QGC_FAILED_MSG, CAL_QGC_STARTED_MSG, calibration_log_critical, calibration_log_info, battery_status_s::connected, fd, hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), actuator_armed_s::in_esc_calibration_mode, OK, ORB_ID, PWM_OUTPUT0_DEVICE_PATH, PWM_SERVO_ARM, PWM_SERVO_CLEAR_ARM_OK, PWM_SERVO_DISARM, PWM_SERVO_SET_ARM_OK, PWM_SERVO_SET_FORCE_SAFETY_OFF, PWM_SERVO_SET_FORCE_SAFETY_ON, px4_close(), px4_ioctl(), px4_open(), and battery_status_s::timestamp.

Referenced by commander_low_prio_loop(), and commander_main().

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