mirror of https://github.com/ArduPilot/ardupilot
Copter: move try_send_message handling of RC_CHANNELS up
This commit is contained in:
parent
9e1811027d
commit
6dd9f50f7c
|
@ -150,7 +150,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
#endif
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50),
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75),
|
||||
SCHED_TASK(read_receiver_rssi, 10, 75),
|
||||
#if RPM_ENABLED == ENABLED
|
||||
SCHED_TASK(rpm_update, 10, 200),
|
||||
#endif
|
||||
|
|
|
@ -378,9 +378,6 @@ private:
|
|||
AP_BoardConfig_CAN BoardConfig_CAN;
|
||||
#endif
|
||||
|
||||
// receiver RSSI
|
||||
uint8_t receiver_rssi;
|
||||
|
||||
// Failsafe
|
||||
struct {
|
||||
uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
|
||||
|
@ -886,7 +883,6 @@ private:
|
|||
void compass_accumulate(void);
|
||||
void init_optflow();
|
||||
void update_optical_flow(void);
|
||||
void read_receiver_rssi(void);
|
||||
void compass_cal_update(void);
|
||||
void accel_cal_update(void);
|
||||
void init_proximity();
|
||||
|
|
|
@ -334,11 +334,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
|
|||
copter.send_nav_controller_output(chan);
|
||||
break;
|
||||
|
||||
case MSG_RADIO_IN:
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
|
||||
send_radio_in(copter.receiver_rssi);
|
||||
break;
|
||||
|
||||
case MSG_SERVO_OUTPUT_RAW:
|
||||
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
||||
send_servo_output_raw(false);
|
||||
|
|
|
@ -162,13 +162,6 @@ void Copter::update_optical_flow(void)
|
|||
}
|
||||
#endif // OPTFLOW == ENABLED
|
||||
|
||||
// read the receiver RSSI as an 8 bit number for MAVLink
|
||||
// RC_CHANNELS_SCALED message
|
||||
void Copter::read_receiver_rssi(void)
|
||||
{
|
||||
receiver_rssi = rssi.read_receiver_rssi_uint8();
|
||||
}
|
||||
|
||||
void Copter::compass_cal_update()
|
||||
{
|
||||
static uint32_t compass_cal_stick_gesture_begin = 0;
|
||||
|
|
Loading…
Reference in New Issue