mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: make Location(Vector3f) require ALTFRAME
This commit is contained in:
parent
dce01fbb43
commit
1b584a95ba
|
@ -405,7 +405,7 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert object's position as an offset from EKF origin to Location
|
// convert object's position as an offset from EKF origin to Location
|
||||||
const Location item_loc(Vector3f(_database.items[idx].pos.x * 100.0f, _database.items[idx].pos.y * 100.0f, _database.items[idx].pos.z * 100.0f));
|
const Location item_loc(Vector3f(_database.items[idx].pos.x * 100.0f, _database.items[idx].pos.y * 100.0f, _database.items[idx].pos.z * 100.0f), Location::AltFrame::ABOVE_ORIGIN);
|
||||||
|
|
||||||
mavlink_msg_adsb_vehicle_send(chan,
|
mavlink_msg_adsb_vehicle_send(chan,
|
||||||
idx,
|
idx,
|
||||||
|
@ -476,5 +476,3 @@ AP_OADatabase *oadatabase()
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -140,7 +140,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t
|
||||||
Vector2f origin_pos;
|
Vector2f origin_pos;
|
||||||
if ((_path_idx_returned > 0) && get_shortest_path_point(_path_idx_returned-1, origin_pos)) {
|
if ((_path_idx_returned > 0) && get_shortest_path_point(_path_idx_returned-1, origin_pos)) {
|
||||||
// convert offset from ekf origin to Location
|
// convert offset from ekf origin to Location
|
||||||
Location temp_loc(Vector3f(origin_pos.x, origin_pos.y, 0.0f));
|
Location temp_loc(Vector3f(origin_pos.x, origin_pos.y, 0.0f), Location::AltFrame::ABOVE_ORIGIN);
|
||||||
origin_new = temp_loc;
|
origin_new = temp_loc;
|
||||||
} else {
|
} else {
|
||||||
// for first point use current loc as origin
|
// for first point use current loc as origin
|
||||||
|
@ -148,7 +148,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t
|
||||||
}
|
}
|
||||||
|
|
||||||
// convert offset from ekf origin to Location
|
// convert offset from ekf origin to Location
|
||||||
Location temp_loc(Vector3f(dest_pos.x, dest_pos.y, 0.0f));
|
Location temp_loc(Vector3f(dest_pos.x, dest_pos.y, 0.0f), Location::AltFrame::ABOVE_ORIGIN);
|
||||||
destination_new = destination;
|
destination_new = destination;
|
||||||
destination_new.lat = temp_loc.lat;
|
destination_new.lat = temp_loc.lat;
|
||||||
destination_new.lng = temp_loc.lng;
|
destination_new.lng = temp_loc.lng;
|
||||||
|
@ -904,4 +904,3 @@ bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos)
|
||||||
// we should never reach here but just in case
|
// we should never reach here but just in case
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue