mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
uORB delete unused pwm_output
This commit is contained in:
@@ -73,7 +73,6 @@ set(msg_files
|
||||
multirotor_motor_limits.msg
|
||||
offboard_control_mode.msg
|
||||
optical_flow.msg
|
||||
output_pwm.msg
|
||||
parameter_update.msg
|
||||
position_setpoint.msg
|
||||
position_setpoint_triplet.msg
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
uint8 PWM_OUTPUT_MAX_CHANNELS = 16
|
||||
uint16[16] values
|
||||
uint32 channel_count
|
||||
@@ -48,7 +48,7 @@ msg_id_map = {
|
||||
'multirotor_motor_limits': 43,
|
||||
'offboard_control_mode': 44,
|
||||
'optical_flow': 45,
|
||||
'output_pwm': 46,
|
||||
|
||||
'parameter_update': 47,
|
||||
'position_setpoint': 48,
|
||||
'position_setpoint_triplet': 49,
|
||||
@@ -86,7 +86,7 @@ msg_id_map = {
|
||||
'vehicle_control_mode': 81,
|
||||
'vehicle_force_setpoint': 82,
|
||||
'vehicle_global_position': 83,
|
||||
'vehicle_global_velocity_setpoint': 84,
|
||||
|
||||
'vehicle_gps_position': 85,
|
||||
'vehicle_land_detected': 86,
|
||||
'vehicle_local_position': 87,
|
||||
|
||||
@@ -35,8 +35,7 @@
|
||||
* @file PWM servo output interface.
|
||||
*
|
||||
* Servo values can be set with the PWM_SERVO_SET ioctl, by writing a
|
||||
* pwm_output_values structure to the device, or by publishing to the
|
||||
* output_pwm ORB topic.
|
||||
* pwm_output_values structure to the device
|
||||
* Writing a value of 0 to a channel suppresses any output for that
|
||||
* channel.
|
||||
*/
|
||||
@@ -45,8 +44,6 @@
|
||||
|
||||
#include <px4_defines.h>
|
||||
|
||||
#include "uORB/topics/output_pwm.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
@@ -64,11 +61,12 @@ __BEGIN_DECLS
|
||||
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output"
|
||||
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
|
||||
|
||||
#define pwm_output_values output_pwm_s
|
||||
#define PWM_OUTPUT_MAX_CHANNELS 16
|
||||
|
||||
#ifndef PWM_OUTPUT_MAX_CHANNELS
|
||||
#define PWM_OUTPUT_MAX_CHANNELS output_pwm_s::PWM_OUTPUT_MAX_CHANNELS
|
||||
#endif
|
||||
struct pwm_output_values {
|
||||
uint32_t channel_count;
|
||||
uint16_t values[16];
|
||||
};
|
||||
|
||||
/**
|
||||
* Maximum number of PWM output channels supported by the device.
|
||||
|
||||
@@ -78,7 +78,6 @@
|
||||
#define RC_INPUT_MAX_DEADZONE_US 500
|
||||
|
||||
#include <uORB/topics/input_rc.h>
|
||||
#define pwm_output_values output_pwm_s
|
||||
#define rc_input_values input_rc_s
|
||||
|
||||
/**
|
||||
|
||||
Reference in New Issue
Block a user