mirror of https://github.com/ArduPilot/ardupilot
better crosstrack
This commit is contained in:
parent
abed7fa5f2
commit
63c884a6df
|
@ -190,12 +190,18 @@ static void calc_nav_pitch()
|
||||||
|
|
||||||
static void calc_nav_roll()
|
static void calc_nav_roll()
|
||||||
{
|
{
|
||||||
float psi_dot_cmd = g.pidNavRoll.kP() * (bearing_error / 100.0);
|
//float psi_dot_cmd = g.pidNavRoll.kP() * (bearing_error / 100.0);
|
||||||
|
|
||||||
nav_roll = (100 * ToDeg(atan((psi_dot_cmd * ((float)g_gps->ground_speed)) / 981.0)));
|
//nav_roll = (100 * ToDeg(atan((psi_dot_cmd * ((float)g_gps->ground_speed)) / 981.0)));
|
||||||
|
|
||||||
//printf("nvrl %ld err %ld psi %f gps gs %ld COG %ld\n",nav_roll,bearing_error,psi_dot_cmd,g_gps->ground_speed,g_gps->ground_course);
|
//printf("nvrl %ld err %ld psi %f gps gs %ld COG %ld\n",nav_roll,bearing_error,psi_dot_cmd,g_gps->ground_speed,g_gps->ground_course);
|
||||||
|
|
||||||
|
long psi_dot_cmd = g.pidNavRoll.kP() * bearing_error;
|
||||||
|
|
||||||
|
nav_roll = (100 * ToDeg(atan((psi_dot_cmd * g_gps->ground_speed) / 9810000.0)));
|
||||||
|
|
||||||
|
// printf("nvrl %ld err %ld psi %ld gps gs %ld COG %ld\n",nav_roll,bearing_error,psi_dot_cmd,g_gps->ground_speed,g_gps->ground_course);
|
||||||
|
|
||||||
Vector3f omega;
|
Vector3f omega;
|
||||||
omega = dcm.get_gyro();
|
omega = dcm.get_gyro();
|
||||||
|
|
||||||
|
|
|
@ -180,9 +180,9 @@ static void set_next_WP(struct Location *wp)
|
||||||
scaleLongDown = cos(rads);
|
scaleLongDown = cos(rads);
|
||||||
scaleLongUp = 1.0f/cos(rads);
|
scaleLongUp = 1.0f/cos(rads);
|
||||||
// this is handy for the groundstation
|
// this is handy for the groundstation
|
||||||
wp_totalDistance = get_distance(&prev_WP, &next_WP);
|
wp_totalDistance = get_distance(¤t_loc, &next_WP);
|
||||||
wp_distance = wp_totalDistance;
|
wp_distance = wp_totalDistance;
|
||||||
target_bearing = get_bearing(&prev_WP, &next_WP);
|
target_bearing = get_bearing(¤t_loc, &next_WP);
|
||||||
nav_bearing = target_bearing;
|
nav_bearing = target_bearing;
|
||||||
|
|
||||||
// to check if we have missed the WP
|
// to check if we have missed the WP
|
||||||
|
|
|
@ -183,7 +183,7 @@ static void update_crosstrack(void)
|
||||||
|
|
||||||
static void reset_crosstrack()
|
static void reset_crosstrack()
|
||||||
{
|
{
|
||||||
crosstrack_bearing = get_bearing(¤t_loc, &next_WP); // Used for track following
|
crosstrack_bearing = get_bearing(&prev_WP, &next_WP); // Used for track following
|
||||||
}
|
}
|
||||||
|
|
||||||
static long get_distance(struct Location *loc1, struct Location *loc2)
|
static long get_distance(struct Location *loc1, struct Location *loc2)
|
||||||
|
|
Loading…
Reference in New Issue