Skip to content

Commit 0460147

Browse files
committed
Copter: guided mode yaw fix
Nose of copter now points at next guided point if it is more than 10m away
1 parent a0bf49a commit 0460147

File tree

2 files changed

+31
-5
lines changed

2 files changed

+31
-5
lines changed

ArduCopter/GCS_Mavlink.pde

+2-5
Original file line numberDiff line numberDiff line change
@@ -1729,11 +1729,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
17291729
}
17301730

17311731
if(packet.current == 2) { //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission
1732-
// switch to guided mode
1733-
set_mode(GUIDED);
1734-
1735-
// set wp_nav's destination
1736-
wp_nav.set_destination(pv_location_to_vector(tell_command));
1732+
// initiate guided mode
1733+
do_guided(&tell_command);
17371734

17381735
// verify we recevied the command
17391736
mavlink_msg_mission_ack_send(

ArduCopter/commands_logic.pde

+29
Original file line numberDiff line numberDiff line change
@@ -843,6 +843,35 @@ static bool verify_nav_roi()
843843
// Do (Now) commands
844844
/********************************************************************************/
845845

846+
// do_guided - start guided mode
847+
// this is not actually a mission command but rather a
848+
static void do_guided(const struct Location *cmd)
849+
{
850+
bool first_time = false;
851+
// switch to guided mode if we're not already in guided mode
852+
if (control_mode != GUIDED) {
853+
set_mode(GUIDED);
854+
first_time = true;
855+
}
856+
857+
// set wp_nav's destination
858+
Vector3f pos = pv_location_to_vector(*cmd);
859+
wp_nav.set_destination(pos);
860+
861+
// initialise wp_bearing for reporting purposes
862+
wp_bearing = wp_nav.get_bearing_to_destination();
863+
864+
// point nose at next waypoint if it is more than 10m away
865+
if (yaw_mode == YAW_LOOK_AT_NEXT_WP) {
866+
// get distance to new location
867+
wp_distance = wp_nav.get_distance_to_destination();
868+
// set original_wp_bearing to point at next waypoint
869+
if (wp_distance >= 1000 || first_time) {
870+
original_wp_bearing = wp_bearing;
871+
}
872+
}
873+
}
874+
846875
static void do_change_speed()
847876
{
848877
wp_nav.set_horizontal_velocity(command_cond_queue.p1 * 100);

0 commit comments

Comments
 (0)