|
|
|
@ -190,10 +190,10 @@ void ModeAuto::start_guided(const Location& loc)
@@ -190,10 +190,10 @@ void ModeAuto::start_guided(const Location& loc)
|
|
|
|
|
Location loc_sanitised = loc; |
|
|
|
|
if ((loc_sanitised.lat != 0) || (loc_sanitised.lng != 0)) { |
|
|
|
|
location_sanitize(rover.current_loc, loc_sanitised); |
|
|
|
|
guided_target = loc_sanitised; |
|
|
|
|
guided_target_valid = true; |
|
|
|
|
guided_target.loc = loc_sanitised; |
|
|
|
|
guided_target.valid = true; |
|
|
|
|
} else { |
|
|
|
|
guided_target_valid = false; |
|
|
|
|
guided_target.valid = false; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -201,21 +201,21 @@ void ModeAuto::start_guided(const Location& loc)
@@ -201,21 +201,21 @@ void ModeAuto::start_guided(const Location& loc)
|
|
|
|
|
// send latest position target to offboard navigation system
|
|
|
|
|
void ModeAuto::send_guided_position_target() |
|
|
|
|
{ |
|
|
|
|
if (!guided_target_valid) { |
|
|
|
|
if (!guided_target.valid) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// send at maximum of 1hz
|
|
|
|
|
uint32_t now_ms = AP_HAL::millis(); |
|
|
|
|
if ((guided_target_sent_ms == 0) || (now_ms - guided_target_sent_ms > AUTO_GUIDED_SEND_TARGET_MS)) { |
|
|
|
|
guided_target_sent_ms = now_ms; |
|
|
|
|
if ((guided_target.last_sent_ms == 0) || (now_ms - guided_target.last_sent_ms > AUTO_GUIDED_SEND_TARGET_MS)) { |
|
|
|
|
guided_target.last_sent_ms = now_ms; |
|
|
|
|
|
|
|
|
|
// get system id and component id of offboard navigation system
|
|
|
|
|
uint8_t sysid = 0; |
|
|
|
|
uint8_t compid = 0; |
|
|
|
|
mavlink_channel_t chan; |
|
|
|
|
if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_ONBOARD_CONTROLLER, sysid, compid, chan)) { |
|
|
|
|
gcs().chan(chan-MAVLINK_COMM_0).send_set_position_target_global_int(sysid, compid, guided_target); |
|
|
|
|
gcs().chan(chan-MAVLINK_COMM_0).send_set_position_target_global_int(sysid, compid, guided_target.loc); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|