PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/tasks.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/getopt.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <math.h>
#include <poll.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
#include "systemlib/err.h"
#include "uORB/topics/actuator_controls.h"
Go to the source code of this file.
Enumerations | |
enum | RampState { RAMP_INIT, RAMP_MIN, RAMP_RAMP, RAMP_WAIT } |
enum | Mode { RAMP, SINE, SQUARE } |
Functions | |
__EXPORT int | motor_ramp_main (int argc, char *argv[]) |
motor_ramp management function. More... | |
int | motor_ramp_thread_main (int argc, char *argv[]) |
Mainloop of motor_ramp. More... | |
bool | min_pwm_valid (int pwm_value) |
bool | max_pwm_valid (int pwm_value) |
int | set_min_pwm (int fd, unsigned long max_channels, int pwm_value) |
int | set_out (int fd, unsigned long max_channels, float output) |
int | prepare (int fd, unsigned long *max_channels) |
static void | usage (const char *reason) |
Print the correct usage. More... | |
Variables | |
static bool | _thread_should_exit = false |
motor_ramp exit flag More... | |
static bool | _thread_running = false |
motor_ramp status flag More... | |
static int | _motor_ramp_task |
Handle of motor_ramp task / thread. More... | |
static float | _ramp_time |
static int | _min_pwm |
static int | _max_pwm |
static Mode | _mode |
static const char * | _mode_c |
static const char * | _pwm_output_dev = "/dev/pwm_output0" |
Definition in file motor_ramp.cpp.
enum Mode |
Enumerator | |
---|---|
RAMP | |
SINE | |
SQUARE |
Definition at line 69 of file motor_ramp.cpp.
enum RampState |
Enumerator | |
---|---|
RAMP_INIT | |
RAMP_MIN | |
RAMP_RAMP | |
RAMP_WAIT |
Definition at line 62 of file motor_ramp.cpp.
bool max_pwm_valid | ( | int | pwm_value | ) |
Definition at line 267 of file motor_ramp.cpp.
References _min_pwm.
Referenced by motor_ramp_main().
bool min_pwm_valid | ( | int | pwm_value | ) |
Definition at line 262 of file motor_ramp.cpp.
Referenced by motor_ramp_main().
int motor_ramp_main | ( | int | argc, |
char * | argv[] | ||
) |
motor_ramp management function.
The motor_ramp app only briefly exists to start the background job.
The stack size assigned in the Makefile does only apply to this management task.
The actual stack size should be set in the call to task_create().
Definition at line 152 of file motor_ramp.cpp.
References _max_pwm, _min_pwm, _mode, _mode_c, _motor_ramp_task, _pwm_output_dev, _ramp_time, _thread_running, _thread_should_exit, max_pwm_valid(), min_pwm_valid(), motor_ramp_thread_main(), RAMP, SINE, SQUARE, and usage().
int motor_ramp_thread_main | ( | int | argc, |
char * | argv[] | ||
) |
Mainloop of motor_ramp.
Definition at line 362 of file motor_ramp.cpp.
References _max_pwm, _min_pwm, _mode, _mode_c, _pwm_output_dev, _ramp_time, _thread_running, _thread_should_exit, dt, f(), fd, hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), OK, prepare(), PWM_SERVO_ENTER_TEST_MODE, PWM_SERVO_EXIT_TEST_MODE, PWM_SERVO_GET, PWM_SERVO_GET_COUNT, PWM_SERVO_GET_MIN_PWM, PWM_SERVO_SET, PWM_SERVO_SET_MIN_PWM, PWM_SERVO_SET_MODE, px4_close(), px4_ioctl(), px4_open(), RAMP, RAMP_INIT, RAMP_MIN, RAMP_RAMP, RAMP_WAIT, set_min_pwm(), set_out(), SINE, SQUARE, start(), and pwm_output_values::values.
Referenced by motor_ramp_main().
int prepare | ( | int | fd, |
unsigned long * | max_channels | ||
) |
Definition at line 312 of file motor_ramp.cpp.
References OK, orb_check(), orb_copy(), ORB_ID_VEHICLE_ATTITUDE_CONTROLS, orb_subscribe(), PWM_SERVO_ARM, PWM_SERVO_GET_COUNT, PWM_SERVO_SET_ARM_OK, PWM_SERVO_SET_FORCE_SAFETY_OFF, and px4_ioctl().
Referenced by motor_ramp_thread_main().
int set_min_pwm | ( | int | fd, |
unsigned long | max_channels, | ||
int | pwm_value | ||
) |
Definition at line 272 of file motor_ramp.cpp.
References pwm_output_values::channel_count, OK, PWM_SERVO_SET_MIN_PWM, px4_ioctl(), and pwm_output_values::values.
Referenced by motor_ramp_thread_main().
int set_out | ( | int | fd, |
unsigned long | max_channels, | ||
float | output | ||
) |
Definition at line 294 of file motor_ramp.cpp.
References _max_pwm, _min_pwm, OK, and PWM_SERVO_SET.
Referenced by motor_ramp_thread_main().
|
static |
Print the correct usage.
Definition at line 111 of file motor_ramp.cpp.
References f().
Referenced by motor_ramp_main().
|
static |
Definition at line 80 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), motor_ramp_thread_main(), and set_out().
|
static |
Definition at line 79 of file motor_ramp.cpp.
Referenced by max_pwm_valid(), motor_ramp_main(), motor_ramp_thread_main(), and set_out().
|
static |
Definition at line 81 of file motor_ramp.cpp.
Referenced by PrecLand::get_mode(), DShotOutput::get_mode(), PX4FMU::get_mode(), Mavlink::get_mode(), motor_ramp_main(), motor_ramp_thread_main(), and PrecLand::set_mode().
|
static |
Definition at line 82 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), and motor_ramp_thread_main().
|
static |
Handle of motor_ramp task / thread.
Definition at line 77 of file motor_ramp.cpp.
Referenced by motor_ramp_main().
|
static |
Definition at line 83 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), and motor_ramp_thread_main().
|
static |
Definition at line 78 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), and motor_ramp_thread_main().
|
static |
motor_ramp status flag
Definition at line 76 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), and motor_ramp_thread_main().
|
static |
motor_ramp exit flag
Definition at line 75 of file motor_ramp.cpp.
Referenced by motor_ramp_main(), and motor_ramp_thread_main().