mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: alphabetise method declarations
This commit is contained in:
parent
c8c5944b5f
commit
c6d761c78f
@ -194,36 +194,69 @@ private:
|
||||
static const AP_Param::Info var_info[];
|
||||
static const struct LogStructure log_structure[];
|
||||
|
||||
// AntennaTracker.cpp
|
||||
void one_second_loop();
|
||||
void ten_hz_logging_loop();
|
||||
void send_extended_status1(mavlink_channel_t chan);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void gcs_retry_deferred(void);
|
||||
void load_parameters(void);
|
||||
|
||||
// capabilities.cpp
|
||||
void init_capabilities(void);
|
||||
|
||||
// control_auto.cpp
|
||||
void update_auto(void);
|
||||
void calc_angle_error(float pitch, float yaw, bool direction_reversed);
|
||||
void convert_ef_to_bf(float pitch, float yaw, float& bf_pitch, float& bf_yaw);
|
||||
bool convert_bf_to_ef(float pitch, float yaw, float& ef_pitch, float& ef_yaw);
|
||||
bool get_ef_yaw_direction();
|
||||
|
||||
// control_manual.cpp
|
||||
void update_manual(void);
|
||||
|
||||
// control_scan.cpp
|
||||
void update_scan(void);
|
||||
|
||||
// control_servo_test.cpp
|
||||
bool servo_test_set_servo(uint8_t servo_num, uint16_t pwm);
|
||||
|
||||
// GCS_Mavlink.cpp
|
||||
void send_extended_status1(mavlink_channel_t chan);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void gcs_retry_deferred(void);
|
||||
|
||||
// Log.cpp
|
||||
void Log_Write_Attitude();
|
||||
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
||||
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void log_init(void);
|
||||
|
||||
// Parameters.cpp
|
||||
void load_parameters(void);
|
||||
|
||||
// radio.cpp
|
||||
void read_radio();
|
||||
|
||||
// sensors.cpp
|
||||
void update_ahrs();
|
||||
void update_compass(void);
|
||||
void compass_cal_update();
|
||||
void accel_cal_update(void);
|
||||
void update_GPS(void);
|
||||
void handle_battery_failsafe(const char* type_str, const int8_t action);
|
||||
|
||||
// servos.cpp
|
||||
void init_servos();
|
||||
void update_pitch_servo(float pitch);
|
||||
void update_pitch_position_servo(void);
|
||||
void update_pitch_cr_servo(float pitch);
|
||||
void update_pitch_onoff_servo(float pitch);
|
||||
void update_pitch_cr_servo(float pitch);
|
||||
void update_yaw_servo(float yaw);
|
||||
void update_yaw_position_servo(void);
|
||||
void update_yaw_cr_servo(float yaw);
|
||||
void update_yaw_onoff_servo(float yaw);
|
||||
void update_yaw_cr_servo(float yaw);
|
||||
|
||||
// system.cpp
|
||||
void init_tracker();
|
||||
bool get_home_eeprom(struct Location &loc);
|
||||
void set_home_eeprom(struct Location temp);
|
||||
@ -232,6 +265,9 @@ private:
|
||||
void disarm_servos();
|
||||
void prepare_servos();
|
||||
void set_mode(enum ControlMode mode, mode_reason_t reason);
|
||||
bool should_log(uint32_t mask);
|
||||
|
||||
// tracking.cpp
|
||||
void update_vehicle_pos_estimate();
|
||||
void update_tracker_position();
|
||||
void update_bearing_and_distance();
|
||||
@ -240,15 +276,6 @@ private:
|
||||
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
|
||||
void tracking_manual_control(const mavlink_manual_control_t &msg);
|
||||
void update_armed_disarmed();
|
||||
void init_capabilities(void);
|
||||
void compass_cal_update();
|
||||
void Log_Write_Attitude();
|
||||
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
|
||||
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void log_init(void);
|
||||
bool should_log(uint32_t mask);
|
||||
void handle_battery_failsafe(const char* type_str, const int8_t action);
|
||||
|
||||
public:
|
||||
void mavlink_delay_cb();
|
||||
|
Loading…
Reference in New Issue
Block a user