aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/mavlink/mavlink.c3
-rw-r--r--apps/sensors/sensors.cpp2
-rw-r--r--apps/uORB/topics/rc_channels.h5
3 files changed, 5 insertions, 5 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index ea1c511f9..cf6fb077f 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -1416,6 +1416,8 @@ void handleMessage(mavlink_message_t *msg)
memset(&rc_hil, 0, sizeof(rc_hil));
static orb_advert_t rc_pub = 0;
+ rc_hil.timestamp = hrt_absolute_time();
+ rc_hil.chan_count = 4;
rc_hil.chan[0].raw = 1500 + man.x / 2;
rc_hil.chan[1].raw = 1500 + man.y / 2;
rc_hil.chan[2].raw = 1500 + man.r / 2;
@@ -1429,6 +1431,7 @@ void handleMessage(mavlink_message_t *msg)
struct manual_control_setpoint_s mc;
static orb_advert_t mc_pub = 0;
+ mc.timestamp = rc_hil.timestamp;
mc.roll = man.x / 1000.0f;
mc.pitch = man.y / 1000.0f;
mc.yaw = man.r / 1000.0f;
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index f81dfa9b8..a68f6166c 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -960,8 +960,6 @@ Sensors::ppm_poll()
/* Read out values from HRT */
for (unsigned int i = 0; i < channel_limit; i++) {
_rc.chan[i].raw = ppm_buffer[i];
- /* Set the range to +-, then scale up */
- _rc.chan[i].scale = (ppm_buffer[i] - _rc.chan[i].mid) * _rc.chan[i].scaling_factor * 10000;
/* scale around the mid point differently for lower and upper range */
if (ppm_buffer[i] > (_parameters.trim[i] + _parameters.dz[i])) {
diff --git a/apps/uORB/topics/rc_channels.h b/apps/uORB/topics/rc_channels.h
index e34376e82..2c487cf3b 100644
--- a/apps/uORB/topics/rc_channels.h
+++ b/apps/uORB/topics/rc_channels.h
@@ -86,10 +86,9 @@ struct rc_channels_s {
uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
struct {
uint16_t mid; /**< midpoint (0). */
- float scaling_factor; /**< scaling factor from raw counts to 0..1 */
+ float scaling_factor; /**< scaling factor from raw counts to -1..+1 */
uint16_t raw; /**< current raw value */
- int16_t scale;
- float scaled; /**< Scaled */
+ float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
uint16_t override;
enum RC_CHANNELS_STATUS status; /**< status of the channel */
} chan[RC_CHANNELS_FUNCTION_MAX];