Tracker: init member variables

Resolves Coverity warnings
This commit is contained in:
Randy Mackay 2015-06-08 13:14:10 +09:00
parent 6e23d05140
commit 5f53937c6a
2 changed files with 10 additions and 7 deletions

View File

@ -114,7 +114,10 @@ AP_ADC_ADS7844 apm1_adc;
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
Tracker::Tracker(void) Tracker::Tracker(void)
{} {
memset(&current_loc, 0, sizeof(current_loc));
memset(&vehicle, 0, sizeof(vehicle));
}
Tracker tracker; Tracker tracker;

View File

@ -100,9 +100,9 @@ private:
// notification object for LEDs, buzzers etc // notification object for LEDs, buzzers etc
AP_Notify notify; AP_Notify notify;
uint32_t start_time_ms; uint32_t start_time_ms = 0;
bool usb_connected; bool usb_connected = false;
AP_GPS gps; AP_GPS gps;
@ -165,7 +165,7 @@ private:
bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup) bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup)
bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode
bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode
} nav_status; } nav_status = {0.0f, 0.0f, 0.0f, 0.0f, false, false, true, false, false};
// Servo state // Servo state
struct { struct {
@ -173,15 +173,15 @@ private:
bool yaw_upper : 1; // true if yaw servo has been limited from moving to a higher position (i.e. position or rate limited) bool yaw_upper : 1; // true if yaw servo has been limited from moving to a higher position (i.e. position or rate limited)
bool pitch_lower : 1; // true if pitch servo has been limited from moving to a lower position (i.e. position or rate limited) bool pitch_lower : 1; // true if pitch servo has been limited from moving to a lower position (i.e. position or rate limited)
bool pitch_upper : 1; // true if pitch servo has been limited from moving to a higher position (i.e. position or rate limited) bool pitch_upper : 1; // true if pitch servo has been limited from moving to a higher position (i.e. position or rate limited)
} servo_limit; } servo_limit = {true, true, true, true};
// setup the var_info table // setup the var_info table
AP_Param param_loader{var_info}; AP_Param param_loader{var_info};
uint8_t one_second_counter = 0; uint8_t one_second_counter = 0;
bool target_set = false; bool target_set = false;
int8_t slew_dir; int8_t slew_dir = 0;
uint32_t slew_start_ms; uint32_t slew_start_ms = 0;
static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Scheduler::Task scheduler_tasks[];
static const AP_Param::Info var_info[]; static const AP_Param::Info var_info[];