mirror of https://github.com/ArduPilot/ardupilot
ACM: change to use get_bearing_cd() instead of get_bearing()
This commit is contained in:
parent
a5b5546e2a
commit
fb26160d3b
|
@ -2011,7 +2011,7 @@ static void update_navigation()
|
||||||
if(yaw_mode == YAW_LOOK_AT_HOME){
|
if(yaw_mode == YAW_LOOK_AT_HOME){
|
||||||
if(home_is_set){
|
if(home_is_set){
|
||||||
//nav_yaw = point_at_home_yaw();
|
//nav_yaw = point_at_home_yaw();
|
||||||
nav_yaw = get_bearing(¤t_loc, &home);
|
nav_yaw = get_bearing_cd(¤t_loc, &home);
|
||||||
} else {
|
} else {
|
||||||
nav_yaw = 0;
|
nav_yaw = 0;
|
||||||
}
|
}
|
||||||
|
@ -2457,13 +2457,13 @@ static void update_nav_wp()
|
||||||
static void update_auto_yaw()
|
static void update_auto_yaw()
|
||||||
{
|
{
|
||||||
if(wp_control == CIRCLE_MODE){
|
if(wp_control == CIRCLE_MODE){
|
||||||
auto_yaw = get_bearing(¤t_loc, &circle_WP);
|
auto_yaw = get_bearing_cd(¤t_loc, &circle_WP);
|
||||||
|
|
||||||
}else if(wp_control == LOITER_MODE){
|
}else if(wp_control == LOITER_MODE){
|
||||||
// just hold nav_yaw
|
// just hold nav_yaw
|
||||||
|
|
||||||
}else if(yaw_tracking == MAV_ROI_LOCATION){
|
}else if(yaw_tracking == MAV_ROI_LOCATION){
|
||||||
auto_yaw = get_bearing(¤t_loc, &target_WP);
|
auto_yaw = get_bearing_cd(¤t_loc, &target_WP);
|
||||||
|
|
||||||
}else if(yaw_tracking == MAV_ROI_WPNEXT){
|
}else if(yaw_tracking == MAV_ROI_WPNEXT){
|
||||||
// Point towards next WP
|
// Point towards next WP
|
||||||
|
|
|
@ -166,7 +166,7 @@ static void set_next_WP(struct Location *wp)
|
||||||
// this is handy for the groundstation
|
// this is handy for the groundstation
|
||||||
// -----------------------------------
|
// -----------------------------------
|
||||||
wp_distance = get_distance_cm(¤t_loc, &next_WP);
|
wp_distance = get_distance_cm(¤t_loc, &next_WP);
|
||||||
target_bearing = get_bearing(&prev_WP, &next_WP);
|
target_bearing = get_bearing_cd(&prev_WP, &next_WP);
|
||||||
|
|
||||||
// calc the location error:
|
// calc the location error:
|
||||||
calc_location_error(&next_WP);
|
calc_location_error(&next_WP);
|
||||||
|
|
|
@ -874,7 +874,7 @@ static void do_nav_roi()
|
||||||
if( camera_mount.get_mount_type() == AP_Mount::k_tilt_roll ) {
|
if( camera_mount.get_mount_type() == AP_Mount::k_tilt_roll ) {
|
||||||
yaw_tracking = MAV_ROI_LOCATION;
|
yaw_tracking = MAV_ROI_LOCATION;
|
||||||
target_WP = command_nav_queue;
|
target_WP = command_nav_queue;
|
||||||
auto_yaw = get_bearing(¤t_loc, &target_WP);
|
auto_yaw = get_bearing_cd(¤t_loc, &target_WP);
|
||||||
}
|
}
|
||||||
// send the command to the camera mount
|
// send the command to the camera mount
|
||||||
camera_mount.set_roi_cmd(&command_nav_queue);
|
camera_mount.set_roi_cmd(&command_nav_queue);
|
||||||
|
@ -889,6 +889,6 @@ static void do_nav_roi()
|
||||||
// if we have no camera mount simply rotate the quad
|
// if we have no camera mount simply rotate the quad
|
||||||
yaw_tracking = MAV_ROI_LOCATION;
|
yaw_tracking = MAV_ROI_LOCATION;
|
||||||
target_WP = command_nav_queue;
|
target_WP = command_nav_queue;
|
||||||
auto_yaw = get_bearing(¤t_loc, &target_WP);
|
auto_yaw = get_bearing_cd(¤t_loc, &target_WP);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -12,8 +12,8 @@ static void navigate()
|
||||||
|
|
||||||
// target_bearing is where we should be heading
|
// target_bearing is where we should be heading
|
||||||
// --------------------------------------------
|
// --------------------------------------------
|
||||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
target_bearing = get_bearing_cd(¤t_loc, &next_WP);
|
||||||
home_to_copter_bearing = get_bearing(&home, ¤t_loc);
|
home_to_copter_bearing = get_bearing_cd(&home, ¤t_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool check_missed_wp()
|
static bool check_missed_wp()
|
||||||
|
|
Loading…
Reference in New Issue