mirror of https://github.com/ArduPilot/ardupilot
Rover: follow uses local desired_yaw_cd
reducing dependency on shared _desired_yaw_cd with the hope that it can eventually be removed also minor comment update for desired_yaw_cd
This commit is contained in:
parent
2b654983a9
commit
1f2500d268
|
@ -205,7 +205,7 @@ protected:
|
|||
// private members for waypoint navigation
|
||||
float _distance_to_destination; // distance from vehicle to final destination in meters
|
||||
bool _reached_destination; // true once the vehicle has reached the destination
|
||||
float _desired_yaw_cd; // desired yaw in centi-degrees
|
||||
float _desired_yaw_cd; // desired yaw in centi-degrees. used in Auto, Guided and Loiter
|
||||
float _desired_speed; // desired speed in m/s
|
||||
};
|
||||
|
||||
|
|
|
@ -11,9 +11,6 @@ bool ModeFollow::_enter()
|
|||
// initialise waypoint speed
|
||||
set_desired_speed_to_default();
|
||||
|
||||
// initialise heading to current heading
|
||||
_desired_yaw_cd = ahrs.yaw_sensor;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -64,10 +61,10 @@ void ModeFollow::update()
|
|||
}
|
||||
|
||||
// calculate vehicle heading
|
||||
_desired_yaw_cd = wrap_180_cd(atan2f(desired_velocity_ne.y, desired_velocity_ne.x) * DEGX100);
|
||||
const float desired_yaw_cd = wrap_180_cd(atan2f(desired_velocity_ne.y, desired_velocity_ne.x) * DEGX100);
|
||||
|
||||
// run steering and throttle controllers
|
||||
calc_steering_to_heading(_desired_yaw_cd);
|
||||
calc_steering_to_heading(desired_yaw_cd);
|
||||
calc_throttle(desired_speed, true);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue