mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Remove unused function, remove unnecessary angle wrapping.
This commit is contained in:
parent
bccb07cbd0
commit
46d20c2d6b
@ -313,10 +313,12 @@ AP_Mount::calc_GPS_target_angle(struct Location *target)
|
||||
_roll_control_angle = 0;
|
||||
_pitch_control_angle = atan2(GPS_vector_z, target_distance);
|
||||
_yaw_control_angle = atan2(GPS_vector_x, GPS_vector_y);
|
||||
/*
|
||||
// Converts +/- 180 into 0-360.
|
||||
if(_yaw_control_angle<0){
|
||||
_yaw_control_angle += 2*M_PI;
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
/// Stabilizes mount relative to the Earth's frame
|
||||
@ -365,13 +367,6 @@ AP_Mount::stabilize()
|
||||
}
|
||||
}
|
||||
|
||||
// This function is needed to let the HIL code compile
|
||||
long
|
||||
AP_Mount::rc_map(RC_Channel_aux* rc_ch)
|
||||
{
|
||||
return (rc_ch->radio_in - rc_ch->radio_min) * (rc_ch->angle_max - rc_ch->angle_min) / (rc_ch->radio_max - rc_ch->radio_min) + rc_ch->angle_min;
|
||||
}
|
||||
|
||||
// For testing and development. Called in the medium loop.
|
||||
void
|
||||
AP_Mount::debug_output()
|
||||
|
@ -64,7 +64,6 @@ private:
|
||||
// internal methods
|
||||
void calc_GPS_target_angle(struct Location *target);
|
||||
void stabilize();
|
||||
long rc_map(RC_Channel_aux* rc_ch);
|
||||
|
||||
//members
|
||||
AP_AHRS *_ahrs; ///< Rotation matrix from earth to plane.
|
||||
|
Loading…
Reference in New Issue
Block a user