From 4f0e090e88031f82957e87bfd7ef94269442e54a Mon Sep 17 00:00:00 2001
From: MaEtUgR <maetugr@gmail.com>
Date: Thu, 28 Jun 2018 19:04:03 +0200
Subject: [PATCH] drv_rc_input: replace useless rc_input_values define

---
 src/drivers/drv_rc_input.h                  | 4 +---
 src/drivers/px4io/px4io.cpp                 | 6 +++---
 src/modules/mavlink/mavlink_messages.cpp    | 4 ++--
 src/modules/mavlink/mavlink_receiver.cpp    | 4 ++--
 src/modules/sensors/parameters.h            | 2 +-
 src/modules/sensors/rc_update.cpp           | 3 ++-
 src/modules/simulator/simulator.h           | 2 +-
 src/modules/simulator/simulator_mavlink.cpp | 2 +-
 src/modules/syslink/syslink_main.cpp        | 2 +-
 src/systemcmds/tests/test_ppm_loopback.c    | 4 ++--
 src/systemcmds/tests/test_rc.c              | 5 ++---
 11 files changed, 18 insertions(+), 20 deletions(-)

diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 674dd78b31..bcf59df685 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -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.
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 8adfab22f4..ed55d47393 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -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);
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index ec6e121102..641c5e9b16 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -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)) {
 
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 9a7e2f3cb2..3bd03170de 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -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;
 
diff --git a/src/modules/sensors/parameters.h b/src/modules/sensors/parameters.h
index afdfc31e3c..8bb5712c5b 100644
--- a/src/modules/sensors/parameters.h
+++ b/src/modules/sensors/parameters.h
@@ -47,7 +47,7 @@
 #include <mathlib/mathlib.h>
 
 #include <uORB/topics/rc_parameter_map.h>
-
+#include <uORB/topics/input_rc.h>
 
 namespace sensors
 {
diff --git a/src/modules/sensors/rc_update.cpp b/src/modules/sensors/rc_update.cpp
index 70ce2145b9..f915b9760a 100644
--- a/src/modules/sensors/rc_update.cpp
+++ b/src/modules/sensors/rc_update.cpp
@@ -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 &parameter_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);
 
diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h
index cdd7886036..e6a4b2e958 100644
--- a/src/modules/simulator/simulator.h
+++ b/src/modules/simulator/simulator.h
@@ -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;
diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp
index b6e1aa8642..d8efe0ea25 100644
--- a/src/modules/simulator/simulator_mavlink.cpp
+++ b/src/modules/simulator/simulator_mavlink.cpp
@@ -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;
diff --git a/src/modules/syslink/syslink_main.cpp b/src/modules/syslink/syslink_main.cpp
index 69b6a41fa5..26d0c52223 100644
--- a/src/modules/syslink/syslink_main.cpp
+++ b/src/modules/syslink/syslink_main.cpp
@@ -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;
diff --git a/src/systemcmds/tests/test_ppm_loopback.c b/src/systemcmds/tests/test_ppm_loopback.c
index 445da47888..23023b059f 100644
--- a/src/systemcmds/tests/test_ppm_loopback.c
+++ b/src/systemcmds/tests/test_ppm_loopback.c
@@ -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)) {
diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c
index 590f0b48f5..723af3d88c 100644
--- a/src/systemcmds/tests/test_rc.c
+++ b/src/systemcmds/tests/test_rc.c
@@ -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);
 
-- 
GitLab