mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Rover: removed remaining warnings from PX4 build
This commit is contained in:
parent
d8ba16f9cf
commit
3a28811909
@ -490,6 +490,9 @@ void Rover::update_navigation()
|
||||
}
|
||||
}
|
||||
|
||||
void setup(void);
|
||||
void loop(void);
|
||||
|
||||
void setup(void)
|
||||
{
|
||||
rover.setup();
|
||||
|
@ -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;
|
||||
|
@ -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)
|
||||
{
|
||||
}
|
||||
|
@ -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();
|
||||
|
@ -32,8 +32,3 @@ void Rover::navigate()
|
||||
}
|
||||
|
||||
|
||||
void reached_waypoint()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user