mirror of https://github.com/ArduPilot/ardupilot
Rover: make AHRS attitude member variables private
This commit is contained in:
parent
bcf6578d56
commit
6ca3f31143
|
@ -20,7 +20,7 @@ void Rover::crash_check()
|
|||
}
|
||||
|
||||
// Crashed if pitch/roll > crash_angle
|
||||
if ((g2.crash_angle != 0) && ((fabsf(ahrs.pitch) > radians(g2.crash_angle)) || (fabsf(ahrs.roll) > radians(g2.crash_angle)))) {
|
||||
if ((g2.crash_angle != 0) && ((fabsf(ahrs.get_pitch()) > radians(g2.crash_angle)) || (fabsf(ahrs.get_roll()) > radians(g2.crash_angle)))) {
|
||||
crashed = true;
|
||||
}
|
||||
|
||||
|
|
|
@ -290,7 +290,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled)
|
|||
|
||||
// apply object avoidance to desired speed using half vehicle's maximum deceleration
|
||||
if (avoidance_enabled) {
|
||||
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.yaw, target_speed, rover.G_Dt);
|
||||
g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt);
|
||||
if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) {
|
||||
// we are a sailboat trying to avoid fence, try a tack
|
||||
if (rover.control_mode != &rover.mode_acro) {
|
||||
|
|
|
@ -116,7 +116,7 @@ void ModeCircle::init_target_yaw_rad()
|
|||
// if no position estimate use vehicle yaw
|
||||
Vector2f curr_pos_NE;
|
||||
if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) {
|
||||
target.yaw_rad = AP::ahrs().yaw;
|
||||
target.yaw_rad = AP::ahrs().get_yaw();
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -126,7 +126,7 @@ void ModeCircle::init_target_yaw_rad()
|
|||
|
||||
// if current position is exactly at the center of the circle return vehicle yaw
|
||||
if (is_zero(dist_m)) {
|
||||
target.yaw_rad = AP::ahrs().yaw;
|
||||
target.yaw_rad = AP::ahrs().get_yaw();
|
||||
} else {
|
||||
target.yaw_rad = center_to_veh.angle();
|
||||
}
|
||||
|
|
|
@ -329,7 +329,7 @@ float Sailboat::get_VMG() const
|
|||
return speed;
|
||||
}
|
||||
|
||||
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.yaw)));
|
||||
return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw())));
|
||||
}
|
||||
|
||||
// handle user initiated tack while in acro mode
|
||||
|
@ -340,7 +340,7 @@ void Sailboat::handle_tack_request_acro()
|
|||
}
|
||||
// set tacking heading target to the current angle relative to the true wind but on the new tack
|
||||
currently_tacking = true;
|
||||
tack_heading_rad = wrap_2PI(rover.ahrs.yaw + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.yaw)));
|
||||
tack_heading_rad = wrap_2PI(rover.ahrs.get_yaw() + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.get_yaw())));
|
||||
|
||||
tack_request_ms = AP_HAL::millis();
|
||||
}
|
||||
|
@ -348,7 +348,7 @@ void Sailboat::handle_tack_request_acro()
|
|||
// return target heading in radians when tacking (only used in acro)
|
||||
float Sailboat::get_tack_heading_rad()
|
||||
{
|
||||
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
|
||||
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) < radians(SAILBOAT_TACKING_ACCURACY_DEG) ||
|
||||
((AP_HAL::millis() - tack_request_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) {
|
||||
clear_tack();
|
||||
}
|
||||
|
@ -494,7 +494,7 @@ float Sailboat::calc_heading(float desired_heading_cd)
|
|||
// if we are tacking we maintain the target heading until the tack completes or times out
|
||||
if (currently_tacking) {
|
||||
// check if we have reached target
|
||||
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
|
||||
if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
|
||||
clear_tack();
|
||||
} else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) {
|
||||
// tack has taken too long
|
||||
|
|
Loading…
Reference in New Issue