diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 05d614e4b0..b7bf1aa6fa 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -490,6 +490,9 @@ void Rover::update_navigation() } } +void setup(void); +void loop(void); + void setup(void) { rover.setup(); diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index cb16daa143..9f68bf8041 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -888,9 +888,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else if (is_equal(packet.param5,2.0f)) { // accel trim float trim_roll, trim_pitch; - if(ins.calibrate_trim(trim_roll, trim_pitch)) { + if(rover.ins.calibrate_trim(trim_roll, trim_pitch)) { // reset ahrs's trim to suggested values from calibration routine - ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); + rover.ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); result = MAV_RESULT_ACCEPTED; } else { result = MAV_RESULT_FAILED; diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 6c1dfd66ea..e735c079a8 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -25,10 +25,10 @@ Rover::Rover(void) : channel_steer(NULL), channel_throttle(NULL), channel_learn(NULL), - in_log_download(false), #if defined(HAL_BOARD_LOG_DIRECTORY) DataFlash(HAL_BOARD_LOG_DIRECTORY), #endif + in_log_download(false), modes(&g.mode1), #if AP_AHRS_NAVEKF_AVAILABLE ahrs(ins, barometer, gps, sonar), @@ -42,8 +42,8 @@ Rover::Rover(void) : AP_HAL_MEMBERPROC(&Rover::start_command), AP_HAL_MEMBERPROC(&Rover::verify_command), AP_HAL_MEMBERPROC(&Rover::exit_mission)), - ServoRelayEvents(relay), num_gcs(MAVLINK_COMM_NUM_BUFFERS), + ServoRelayEvents(relay), #if CAMERA == ENABLED camera(&relay), #endif @@ -57,7 +57,6 @@ Rover::Rover(void) : frsky_telemetry(ahrs, battery), #endif home(ahrs.get_home()), - G_Dt(0.02), - radius_of_earth(6378100) + G_Dt(0.02) { } diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 98e83f2a1f..ab1060f3c6 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -249,9 +249,6 @@ private: // before recording our home position (and executing a ground start if we booted with an air start) uint8_t ground_start_count; - // Location & Navigation - const float radius_of_earth; // meters - // true if we have a position estimate from AHRS bool have_position; @@ -452,7 +449,6 @@ private: void read_trim_switch(); void update_events(void); void navigate(); - void reached_waypoint(); void set_control_channels(void); void init_rc_in(); void init_rc_out(); diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp index b0454a4db9..51a3642e86 100644 --- a/APMrover2/navigation.cpp +++ b/APMrover2/navigation.cpp @@ -32,8 +32,3 @@ void Rover::navigate() } -void reached_waypoint() -{ - -} -