mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
drv_rc_input: replace useless rc_input_values define
This commit is contained in:
@@ -42,6 +42,7 @@
|
||||
|
||||
#include <stdint.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
@@ -77,9 +78,6 @@
|
||||
*/
|
||||
#define RC_INPUT_MAX_DEADZONE_US 500
|
||||
|
||||
#include <uORB/topics/input_rc.h>
|
||||
#define rc_input_values input_rc_s
|
||||
|
||||
/**
|
||||
* Input signal type, value is a control position from zero to 100
|
||||
* percent.
|
||||
|
||||
@@ -335,7 +335,7 @@ private:
|
||||
* @param input_rc Input structure to populate.
|
||||
* @return OK if data was returned.
|
||||
*/
|
||||
int io_get_raw_rc_input(rc_input_values &input_rc);
|
||||
int io_get_raw_rc_input(input_rc_s &input_rc);
|
||||
|
||||
/**
|
||||
* Fetch and publish raw RC input data.
|
||||
@@ -1742,7 +1742,7 @@ PX4IO::io_get_status()
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
|
||||
PX4IO::io_get_raw_rc_input(input_rc_s &input_rc)
|
||||
{
|
||||
uint32_t channel_count;
|
||||
int ret;
|
||||
@@ -1849,7 +1849,7 @@ PX4IO::io_publish_raw_rc()
|
||||
{
|
||||
|
||||
/* fetch values from IO */
|
||||
rc_input_values rc_val;
|
||||
input_rc_s rc_val;
|
||||
|
||||
/* set the RC status flag ORDER MATTERS! */
|
||||
rc_val.rc_lost = !(_status & PX4IO_P_STATUS_FLAGS_RC_OK);
|
||||
|
||||
@@ -47,7 +47,6 @@
|
||||
|
||||
#include <commander/px4_custom_mode.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/drv_rc_input.h>
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
#include <lib/matrix/matrix/math.hpp>
|
||||
@@ -70,6 +69,7 @@
|
||||
#include <uORB/topics/estimator_status.h>
|
||||
#include <uORB/topics/geofence_result.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/mavlink_log.h>
|
||||
#include <uORB/topics/vehicle_trajectory_waypoint.h>
|
||||
@@ -3198,7 +3198,7 @@ protected:
|
||||
|
||||
bool send(const hrt_abstime t)
|
||||
{
|
||||
rc_input_values rc;
|
||||
input_rc_s rc;
|
||||
|
||||
if (_rc_sub->update(&_rc_time, &rc)) {
|
||||
|
||||
|
||||
@@ -1821,7 +1821,7 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
|
||||
return;
|
||||
}
|
||||
|
||||
struct rc_input_values rc = {};
|
||||
struct input_rc_s rc = {};
|
||||
|
||||
rc.timestamp = hrt_absolute_time();
|
||||
|
||||
@@ -1881,7 +1881,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
|
||||
|
||||
if (_mavlink->get_manual_input_mode_generation()) {
|
||||
|
||||
struct rc_input_values rc = {};
|
||||
struct input_rc_s rc = {};
|
||||
rc.timestamp = hrt_absolute_time();
|
||||
rc.timestamp_last_signal = rc.timestamp;
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
|
||||
#include <uORB/topics/rc_parameter_map.h>
|
||||
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
namespace sensors
|
||||
{
|
||||
|
||||
@@ -46,6 +46,7 @@
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/input_rc.h>
|
||||
|
||||
using namespace sensors;
|
||||
|
||||
@@ -256,7 +257,7 @@ RCUpdate::rc_poll(const ParameterHandles ¶meter_handles)
|
||||
|
||||
if (rc_updated) {
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
|
||||
struct rc_input_values rc_input;
|
||||
struct input_rc_s rc_input;
|
||||
|
||||
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
|
||||
|
||||
|
||||
@@ -369,7 +369,7 @@ private:
|
||||
uint64_t _hil_ref_timestamp;
|
||||
|
||||
// uORB data containers
|
||||
struct rc_input_values _rc_input;
|
||||
struct input_rc_s _rc_input;
|
||||
struct actuator_outputs_s _actuators[ORB_MULTI_MAX_INSTANCES];
|
||||
struct vehicle_attitude_s _attitude;
|
||||
struct manual_control_setpoint_s _manual;
|
||||
|
||||
@@ -185,7 +185,7 @@ void Simulator::send_controls()
|
||||
}
|
||||
}
|
||||
|
||||
static void fill_rc_input_msg(struct rc_input_values *rc, mavlink_rc_channels_t *rc_channels)
|
||||
static void fill_rc_input_msg(input_rc_s *rc, mavlink_rc_channels_t *rc_channels)
|
||||
{
|
||||
rc->timestamp = hrt_absolute_time();
|
||||
rc->timestamp_last_signal = rc->timestamp;
|
||||
|
||||
@@ -549,7 +549,7 @@ Syslink::handle_raw(syslink_message_t *sys)
|
||||
|
||||
crtp_commander *cmd = (crtp_commander *) &c->data[0];
|
||||
|
||||
struct rc_input_values rc = {};
|
||||
input_rc_s rc = {};
|
||||
|
||||
rc.timestamp = hrt_absolute_time();
|
||||
rc.timestamp_last_signal = rc.timestamp;
|
||||
|
||||
@@ -134,7 +134,7 @@ int test_ppm_loopback(int argc, char *argv[])
|
||||
/* give driver 10 ms to propagate */
|
||||
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
|
||||
struct rc_input_values rc_input;
|
||||
struct input_rc_s rc_input;
|
||||
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
|
||||
usleep(100000);
|
||||
|
||||
@@ -151,7 +151,7 @@ int test_ppm_loopback(int argc, char *argv[])
|
||||
|
||||
|
||||
|
||||
// struct rc_input_values rc;
|
||||
// struct input_rc_s rc;
|
||||
// result = read(ppm_fd, &rc, sizeof(rc));
|
||||
|
||||
// if (result != sizeof(rc)) {
|
||||
|
||||
@@ -61,12 +61,11 @@
|
||||
|
||||
int test_rc(int argc, char *argv[])
|
||||
{
|
||||
|
||||
int _rc_sub = orb_subscribe(ORB_ID(input_rc));
|
||||
|
||||
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
|
||||
struct rc_input_values rc_input;
|
||||
struct rc_input_values rc_last;
|
||||
struct input_rc_s rc_input;
|
||||
struct input_rc_s rc_last;
|
||||
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
|
||||
usleep(100000);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user