Browse Source

Plane: move try_send_message handling of RC_CHANNELS up

master
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
68497f27fa
  1. 1
      ArduPlane/ArduPlane.cpp
  2. 7
      ArduPlane/GCS_Mavlink.cpp
  3. 2
      ArduPlane/GCS_Mavlink.h
  4. 4
      ArduPlane/Plane.h
  5. 7
      ArduPlane/sensors.cpp

1
ArduPlane/ArduPlane.cpp

@ -65,7 +65,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { @@ -65,7 +65,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#endif
SCHED_TASK(one_second_loop, 1, 400),
SCHED_TASK(check_long_failsafe, 3, 400),
SCHED_TASK(read_receiver_rssi, 10, 100),
SCHED_TASK(rpm_update, 10, 100),
SCHED_TASK(airspeed_ratio_update, 1, 100),
SCHED_TASK(update_mount, 50, 100),

7
ArduPlane/GCS_Mavlink.cpp

@ -255,7 +255,7 @@ void Plane::send_servo_out(mavlink_channel_t chan) @@ -255,7 +255,7 @@ void Plane::send_servo_out(mavlink_channel_t chan)
0,
0,
0,
receiver_rssi);
rssi.read_receiver_rssi_uint8());
}
void Plane::send_vfr_hud(mavlink_channel_t chan)
@ -455,11 +455,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) @@ -455,11 +455,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
#endif
break;
case MSG_RADIO_IN:
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
send_radio_in(plane.receiver_rssi);
break;
case MSG_SERVO_OUTPUT_RAW:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
#if HIL_SUPPORT

2
ArduPlane/GCS_Mavlink.h

@ -47,4 +47,6 @@ private: @@ -47,4 +47,6 @@ private:
MAV_MODE base_mode() const override;
uint32_t custom_mode() const override;
MAV_STATE system_status() const override;
uint8_t radio_in_rssi() const;
};

4
ArduPlane/Plane.h

@ -372,9 +372,6 @@ private: @@ -372,9 +372,6 @@ private:
// 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel
int16_t throttle_nudge;
// receiver RSSI
uint8_t receiver_rssi;
// Ground speed
// The amount current ground speed is below min ground speed. Centimeters per second
int32_t groundspeed_undershoot;
@ -924,7 +921,6 @@ private: @@ -924,7 +921,6 @@ private:
void init_rangefinder(void);
void read_rangefinder(void);
void read_airspeed(void);
void read_receiver_rssi(void);
void rpm_update(void);
void button_update(void);
void stats_update();

7
ArduPlane/sensors.cpp

@ -96,13 +96,6 @@ void Plane::read_airspeed(void) @@ -96,13 +96,6 @@ void Plane::read_airspeed(void)
}
}
// read the receiver RSSI as an 8 bit number for MAVLink
// RC_CHANNELS_SCALED message
void Plane::read_receiver_rssi(void)
{
receiver_rssi = rssi.read_receiver_rssi_uint8();
}
/*
update RPM sensors
*/

Loading…
Cancel
Save