Add method to Map to transform Location to GeoLocation
This commit is contained in:
parent
db3c878a54
commit
1a081e8f67
|
@ -1,5 +1,6 @@
|
|||
## Latest Changes
|
||||
* Allow usage of hostname for carla::Client and resolve them to IP address
|
||||
* Added `map.transform_to_geolocation` to transform Location to GNSS GeoLocation
|
||||
* Fixed python client DLL error on Windows
|
||||
|
||||
## CARLA 0.9.4
|
||||
|
|
|
@ -254,6 +254,7 @@
|
|||
- `get_waypoint(location, project_to_road=True)`
|
||||
- `get_topology()`
|
||||
- `generate_waypoints(distance)`
|
||||
- `transform_to_geolocation(location)`
|
||||
- `to_opendrive()`
|
||||
- `save_to_disk(path=self.name)`
|
||||
|
||||
|
|
|
@ -8,60 +8,13 @@
|
|||
#include "carla/Logging.h"
|
||||
#include "carla/client/Map.h"
|
||||
#include "carla/client/detail/Simulator.h"
|
||||
#include "carla/geom/Math.h"
|
||||
#include "carla/sensor/data/GnssEvent.h"
|
||||
#include "carla/StringUtil.h"
|
||||
|
||||
#include <exception>
|
||||
#include <cmath>
|
||||
#include <sstream>
|
||||
#include <limits>
|
||||
|
||||
#if defined(_WIN32) && !defined(_USE_MATH_DEFINES)
|
||||
#define _USE_MATH_DEFINES
|
||||
#include <math.h> // cmath is not enough for MSVC
|
||||
#endif
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
const double EARTH_RADIUS_EQUA = 6378137.0;// earth radius at equator [m]
|
||||
|
||||
// inlined functions to avoid multiple definitions
|
||||
|
||||
/// @brief convert latitude to scale, which is needed by mercator transformations
|
||||
/// @param lat latitude in degrees (DEG)
|
||||
/// @return scale factor
|
||||
/// @note when converting from lat/lon -> mercator and back again,
|
||||
/// or vice versa, use the same scale in both transformations!
|
||||
inline double LatToScale (double lat) {
|
||||
return cos(lat * geom::Math::pi() / 180.0);
|
||||
}
|
||||
|
||||
/// @brief converts lat/lon/scale to mx/my (mx/my in meters if correct scale is given)
|
||||
///
|
||||
template<class float_type>
|
||||
inline void LatLonToMercator (double lat, double lon, double scale, float_type &mx, float_type &my) {
|
||||
mx = scale * lon * geom::Math::pi() * EARTH_RADIUS_EQUA / 180.0;
|
||||
my = scale * EARTH_RADIUS_EQUA * log( tan((90.0+lat) * geom::Math::pi() / 360.0) );
|
||||
}
|
||||
|
||||
/// @brief converts mx/my/scale to lat/lon (mx/my in meters if correct scale is given)
|
||||
inline void MercatorToLatLon (double mx, double my, double scale, double &lat, double &lon) {
|
||||
lon = mx * 180.0 / (geom::Math::pi() * EARTH_RADIUS_EQUA * scale);
|
||||
lat = 360.0 * atan( exp(my/(EARTH_RADIUS_EQUA * scale)) ) / geom::Math::pi() - 90.0;
|
||||
}
|
||||
|
||||
/// @brief adds meters dx/dy to given lat/lon and returns new lat/lon
|
||||
inline void LatLonAddMeters (double lat_start, double lon_start, double dx, double dy, double &lat_end, double &lon_end) {
|
||||
double scale = LatToScale (lat_start);
|
||||
double mx,my;
|
||||
LatLonToMercator (lat_start, lon_start, scale, mx, my);
|
||||
mx += dx;
|
||||
my += dy;
|
||||
MercatorToLatLon (mx, my, scale, lat_end, lon_end);
|
||||
}
|
||||
|
||||
GnssSensor::~GnssSensor() = default;
|
||||
|
||||
void GnssSensor::Listen(CallbackFunctionType callback) {
|
||||
|
@ -76,40 +29,11 @@ namespace client {
|
|||
}
|
||||
|
||||
SharedPtr<Map> map = GetWorld().GetMap();
|
||||
|
||||
DEBUG_ASSERT(map != nullptr);
|
||||
_geo_reference = map->GetGeoReference();
|
||||
|
||||
auto self = boost::static_pointer_cast<GnssSensor>(shared_from_this());
|
||||
|
||||
//parse geo reference string
|
||||
_map_latitude = std::numeric_limits<double>::quiet_NaN();
|
||||
_map_longitude = std::numeric_limits<double>::quiet_NaN();
|
||||
std::vector<std::string> geo_ref_splitted;
|
||||
StringUtil::Split(geo_ref_splitted, map->GetGeoReference(), " ");
|
||||
|
||||
for (auto element: geo_ref_splitted) {
|
||||
std::vector<std::string> geo_ref_key_value;
|
||||
StringUtil::Split(geo_ref_key_value, element, "=");
|
||||
if (geo_ref_key_value.size() != 2u) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (geo_ref_key_value[0] == "+lat_0") {
|
||||
_map_latitude = ParseDouble(geo_ref_key_value[1]);
|
||||
} else if (geo_ref_key_value[0] == "+lon_0") {
|
||||
_map_longitude = ParseDouble(geo_ref_key_value[1]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (std::isnan(_map_latitude) || std::isnan(_map_longitude)) {
|
||||
log_warning(GetDisplayId(), ": cannot parse georeference: '" + map->GetGeoReference() + "'. Using default values.");
|
||||
_map_latitude = 42.0;
|
||||
_map_longitude = 2.0;
|
||||
}
|
||||
|
||||
log_debug(GetDisplayId(), ": map geo reference: latitude ", _map_latitude, ", longitude ", _map_longitude);
|
||||
|
||||
log_debug(GetDisplayId(), ": subscribing to tick event");
|
||||
GetEpisode().Lock()->RegisterOnTickEvent([
|
||||
cb=std::move(callback),
|
||||
|
@ -122,43 +46,26 @@ namespace client {
|
|||
}
|
||||
}
|
||||
});
|
||||
_is_listening = true;
|
||||
}
|
||||
|
||||
double GnssSensor::ParseDouble(std::string const &stringValue) const {
|
||||
double value;
|
||||
std::istringstream istr(stringValue);
|
||||
istr.imbue(std::locale("C"));
|
||||
istr >> value;
|
||||
if (istr.fail() || !istr.eof()) {
|
||||
value = std::numeric_limits<double>::quiet_NaN();
|
||||
}
|
||||
return value;
|
||||
_is_listening = true;
|
||||
}
|
||||
|
||||
SharedPtr<sensor::SensorData> GnssSensor::TickGnssSensor(
|
||||
const Timestamp ×tamp) {
|
||||
try {
|
||||
const auto location = GetLocation();
|
||||
double current_lat, current_lon;
|
||||
|
||||
LatLonAddMeters(_map_latitude, _map_longitude, location.x, location.y, current_lat, current_lon);
|
||||
|
||||
return MakeShared<sensor::data::GnssEvent>(
|
||||
timestamp.frame_count,
|
||||
GetTransform(),
|
||||
current_lat,
|
||||
current_lon,
|
||||
location.z);
|
||||
_geo_reference.Transform(GetLocation()));
|
||||
} catch (const std::exception &e) {
|
||||
/// @todo We need to unsubscribe the sensor.
|
||||
// log_error("LaneDetector:", e.what());
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void GnssSensor::Stop() {
|
||||
/// @todo We need unsubscribe from the world on tick.
|
||||
_is_listening = false;
|
||||
}
|
||||
|
||||
|
|
|
@ -6,14 +6,11 @@
|
|||
#pragma once
|
||||
|
||||
#include "carla/client/Sensor.h"
|
||||
#include <string>
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
|
||||
namespace carla {
|
||||
namespace client {
|
||||
|
||||
class Map;
|
||||
class Vehicle;
|
||||
|
||||
class GnssSensor final : public Sensor {
|
||||
public:
|
||||
|
||||
|
@ -43,14 +40,9 @@ namespace client {
|
|||
|
||||
SharedPtr<sensor::SensorData> TickGnssSensor(const Timestamp ×tamp);
|
||||
|
||||
double ParseDouble(std::string const &stringValue) const;
|
||||
|
||||
double _map_latitude;
|
||||
|
||||
double _map_longitude;
|
||||
geom::GeoLocation _geo_reference;
|
||||
|
||||
bool _is_listening = false;
|
||||
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -23,14 +23,17 @@ namespace client {
|
|||
|
||||
Map::Map(rpc::MapInfo description)
|
||||
: _description(std::move(description)),
|
||||
_map(MakeMap(_description.open_drive_file)) {}
|
||||
_map(MakeMap(_description.open_drive_file)) {
|
||||
if (_map == nullptr) {
|
||||
throw_exception(std::runtime_error("failed to generate map"));
|
||||
}
|
||||
}
|
||||
|
||||
Map::~Map() = default;
|
||||
|
||||
SharedPtr<Waypoint> Map::GetWaypoint(
|
||||
const geom::Location &location,
|
||||
bool project_to_road) const {
|
||||
DEBUG_ASSERT(_map != nullptr);
|
||||
boost::optional<road::element::Waypoint> waypoint;
|
||||
if (project_to_road) {
|
||||
waypoint = _map->GetClosestWaypointOnRoad(location);
|
||||
|
@ -43,7 +46,6 @@ namespace client {
|
|||
}
|
||||
|
||||
Map::TopologyList Map::GetTopology() const {
|
||||
DEBUG_ASSERT(_map != nullptr);
|
||||
namespace re = carla::road::element;
|
||||
std::unordered_map<re::id_type, std::unordered_map<int, SharedPtr<Waypoint>>> waypoints;
|
||||
|
||||
|
@ -82,14 +84,12 @@ namespace client {
|
|||
std::vector<road::element::LaneMarking> Map::CalculateCrossedLanes(
|
||||
const geom::Location &origin,
|
||||
const geom::Location &destination) const {
|
||||
DEBUG_ASSERT(_map != nullptr);
|
||||
return _map->CalculateCrossedLanes(origin, destination);
|
||||
}
|
||||
|
||||
|
||||
std::string Map::GetGeoReference() const {
|
||||
DEBUG_ASSERT(_map != nullptr);
|
||||
const geom::GeoLocation &Map::GetGeoReference() const {
|
||||
return _map->GetData().GetGeoReference();
|
||||
}
|
||||
|
||||
} // namespace client
|
||||
} // namespace carla
|
||||
|
|
|
@ -14,6 +14,7 @@
|
|||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace geom { class GeoLocation; }
|
||||
namespace road { class Map; }
|
||||
namespace client {
|
||||
|
||||
|
@ -54,13 +55,13 @@ namespace client {
|
|||
const geom::Location &origin,
|
||||
const geom::Location &destination) const;
|
||||
|
||||
std::string GetGeoReference() const;
|
||||
const geom::GeoLocation &GetGeoReference() const;
|
||||
|
||||
private:
|
||||
|
||||
rpc::MapInfo _description;
|
||||
const rpc::MapInfo _description;
|
||||
|
||||
SharedPtr<road::Map> _map;
|
||||
const SharedPtr<const road::Map> _map;
|
||||
};
|
||||
|
||||
} // namespace client
|
||||
|
|
|
@ -0,0 +1,76 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
|
||||
#include "carla/geom/Location.h"
|
||||
#include "carla/geom/Math.h"
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#if defined(_WIN32) && !defined(_USE_MATH_DEFINES)
|
||||
# define _USE_MATH_DEFINES
|
||||
# include <math.h> // cmath is not enough for MSVC
|
||||
#endif
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
||||
/// Earth radius at equator [m].
|
||||
static constexpr double EARTH_RADIUS_EQUA = 6378137.0;
|
||||
|
||||
/// Convert latitude to scale, which is needed by mercator
|
||||
/// transformations
|
||||
/// @param lat latitude in degrees (DEG)
|
||||
/// @return scale factor
|
||||
/// @note when converting from lat/lon -> mercator and back again,
|
||||
/// or vice versa, use the same scale in both transformations!
|
||||
static double LatToScale(double lat) {
|
||||
return std::cos(Math::to_radians(lat));
|
||||
}
|
||||
|
||||
/// Converts lat/lon/scale to mx/my (mx/my in meters if correct scale
|
||||
/// is given).
|
||||
template <class float_type>
|
||||
static void LatLonToMercator(double lat, double lon, double scale, float_type &mx, float_type &my) {
|
||||
mx = scale * Math::to_radians(lon) * EARTH_RADIUS_EQUA;
|
||||
my = scale * EARTH_RADIUS_EQUA * std::log(std::tan((90.0 + lat) * Math::pi() / 360.0));
|
||||
}
|
||||
|
||||
/// Converts mx/my/scale to lat/lon (mx/my in meters if correct scale
|
||||
/// is given).
|
||||
static void MercatorToLatLon(double mx, double my, double scale, double &lat, double &lon) {
|
||||
lon = mx * 180.0 / (Math::pi() * EARTH_RADIUS_EQUA * scale);
|
||||
lat = 360.0 * std::atan(std::exp(my / (EARTH_RADIUS_EQUA * scale))) / Math::pi() - 90.0;
|
||||
}
|
||||
|
||||
/// Adds meters dx/dy to given lat/lon and returns new lat/lon.
|
||||
static void LatLonAddMeters(
|
||||
double lat_start,
|
||||
double lon_start,
|
||||
double dx,
|
||||
double dy,
|
||||
double &lat_end,
|
||||
double &lon_end) {
|
||||
double scale = LatToScale(lat_start);
|
||||
double mx, my;
|
||||
LatLonToMercator(lat_start, lon_start, scale, mx, my);
|
||||
mx += dx;
|
||||
my += dy;
|
||||
MercatorToLatLon(mx, my, scale, lat_end, lon_end);
|
||||
}
|
||||
|
||||
GeoLocation GeoLocation::Transform(const Location &location) const {
|
||||
GeoLocation result{0.0, 0.0, altitude + location.z};
|
||||
LatLonAddMeters(
|
||||
latitude, longitude,
|
||||
location.x, location.y,
|
||||
result.latitude, result.longitude);
|
||||
return result;
|
||||
}
|
||||
|
||||
} // namespace geom
|
||||
} // namespace carla
|
|
@ -0,0 +1,62 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
||||
class Location;
|
||||
|
||||
class GeoLocation {
|
||||
public:
|
||||
|
||||
// =========================================================================
|
||||
// -- Public data members --------------------------------------------------
|
||||
// =========================================================================
|
||||
|
||||
double latitude = 0.0;
|
||||
|
||||
double longitude = 0.0;
|
||||
|
||||
double altitude = 0.0;
|
||||
|
||||
// =========================================================================
|
||||
// -- Constructors ---------------------------------------------------------
|
||||
// =========================================================================
|
||||
|
||||
GeoLocation() = default;
|
||||
|
||||
GeoLocation(const GeoLocation &) = default;
|
||||
|
||||
GeoLocation(double latitude, double longitude, double altitude)
|
||||
: latitude(latitude),
|
||||
longitude(longitude),
|
||||
altitude(altitude) {}
|
||||
|
||||
// =========================================================================
|
||||
// -- Transform locations --------------------------------------------------
|
||||
// =========================================================================
|
||||
|
||||
/// Transform the given @a location to a GeoLocation using this as
|
||||
/// geo-reference.
|
||||
GeoLocation Transform(const Location &location) const;
|
||||
|
||||
// =========================================================================
|
||||
// -- Comparison operators -------------------------------------------------
|
||||
// =========================================================================
|
||||
|
||||
bool operator==(const GeoLocation &rhs) const {
|
||||
return (latitude == rhs.latitude) && (longitude == rhs.longitude) && (altitude == rhs.altitude);
|
||||
}
|
||||
|
||||
bool operator!=(const GeoLocation &rhs) const {
|
||||
return !(*this == rhs);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace geom
|
||||
} // namespace carla
|
|
@ -0,0 +1,66 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/opendrive/parser/GeoReferenceParser.h"
|
||||
|
||||
#include "carla/Logging.h"
|
||||
#include "carla/StringUtil.h"
|
||||
|
||||
#include <limits>
|
||||
#include <sstream>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
namespace parser {
|
||||
|
||||
static double ParseDouble(const std::string &string_value) {
|
||||
double value;
|
||||
std::istringstream istr(string_value);
|
||||
istr.imbue(std::locale("C"));
|
||||
istr >> value;
|
||||
if (istr.fail() || !istr.eof()) {
|
||||
value = std::numeric_limits<double>::quiet_NaN();
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
geom::GeoLocation GeoReferenceParser::Parse(const std::string &geo_reference_string) {
|
||||
geom::GeoLocation result{
|
||||
std::numeric_limits<double>::quiet_NaN(),
|
||||
std::numeric_limits<double>::quiet_NaN(),
|
||||
0.0};
|
||||
|
||||
std::vector<std::string> geo_ref_splitted;
|
||||
StringUtil::Split(geo_ref_splitted, geo_reference_string, " ");
|
||||
|
||||
for (auto element: geo_ref_splitted) {
|
||||
std::vector<std::string> geo_ref_key_value;
|
||||
StringUtil::Split(geo_ref_key_value, element, "=");
|
||||
if (geo_ref_key_value.size() != 2u) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (geo_ref_key_value[0] == "+lat_0") {
|
||||
result.latitude = ParseDouble(geo_ref_key_value[1]);
|
||||
} else if (geo_ref_key_value[0] == "+lon_0") {
|
||||
result.longitude = ParseDouble(geo_ref_key_value[1]);
|
||||
}
|
||||
}
|
||||
|
||||
if (std::isnan(result.latitude) || std::isnan(result.longitude)) {
|
||||
log_warning("cannot parse georeference: '" + geo_reference_string + "'. Using default values.");
|
||||
result.latitude = 42.0;
|
||||
result.longitude = 2.0;
|
||||
}
|
||||
|
||||
log_debug("map geo reference: latitude ", result.latitude, ", longitude ", result.longitude);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
} // parser
|
||||
} // opendrive
|
||||
} // carla
|
|
@ -0,0 +1,25 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
|
||||
#include <string>
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
namespace parser {
|
||||
|
||||
class GeoReferenceParser {
|
||||
public:
|
||||
|
||||
static geom::GeoLocation Parse(const std::string &geo_reference_string);
|
||||
};
|
||||
|
||||
} // parser
|
||||
} // opendrive
|
||||
} // carla
|
|
@ -0,0 +1,102 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "carla/opendrive/parser/OpenDriveParser.h"
|
||||
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
#include "carla/opendrive/parser/GeoReferenceParser.h"
|
||||
#include "carla/opendrive/parser/GeometryParser.h"
|
||||
#include "carla/opendrive/parser/JunctionParser.h"
|
||||
#include "carla/opendrive/parser/LaneParser.h"
|
||||
#include "carla/opendrive/parser/ProfilesParser.h"
|
||||
#include "carla/opendrive/parser/RoadLinkParser.h"
|
||||
#include "carla/opendrive/parser/TrafficGroupParser.h"
|
||||
#include "carla/opendrive/parser/TrafficSignParser.h"
|
||||
#include "carla/opendrive/parser/TrafficSignalsParser.h"
|
||||
|
||||
#include "./pugixml/pugixml.hpp"
|
||||
|
||||
bool OpenDriveParser::Parse(
|
||||
const char *xml,
|
||||
carla::opendrive::types::OpenDriveData &out_open_drive_data,
|
||||
XmlInputType inputType,
|
||||
std::string *out_error) {
|
||||
namespace odp = carla::opendrive::parser;
|
||||
|
||||
pugi::xml_document xmlDoc;
|
||||
pugi::xml_parse_result pugiParseResult;
|
||||
|
||||
switch (inputType) {
|
||||
case XmlInputType::FILE: {
|
||||
pugiParseResult = xmlDoc.load_file(xml);
|
||||
} break;
|
||||
|
||||
case XmlInputType::CONTENT: {
|
||||
pugiParseResult = xmlDoc.load_string(xml);
|
||||
} break;
|
||||
|
||||
default: {
|
||||
// TODO(Andrei): Log some kind of error
|
||||
return false;
|
||||
} break;
|
||||
}
|
||||
|
||||
if (pugiParseResult == false) {
|
||||
if (out_error != nullptr) {
|
||||
*out_error = pugiParseResult.description();
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
for (pugi::xml_node road = xmlDoc.child("OpenDRIVE").child("road");
|
||||
road;
|
||||
road = road.next_sibling("road")) {
|
||||
carla::opendrive::types::RoadInformation openDriveRoadInformation;
|
||||
|
||||
openDriveRoadInformation.attributes.name = road.attribute("name").value();
|
||||
openDriveRoadInformation.attributes.id = std::atoi(road.attribute("id").value());
|
||||
openDriveRoadInformation.attributes.length = std::stod(road.attribute("length").value());
|
||||
openDriveRoadInformation.attributes.junction = std::atoi(road.attribute("junction").value());
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
odp::ProfilesParser::Parse(road, openDriveRoadInformation.road_profiles);
|
||||
|
||||
odp::RoadLinkParser::Parse(road.child("link"), openDriveRoadInformation.road_link);
|
||||
odp::TrafficSignalsParser::Parse(road.child("signals"),
|
||||
openDriveRoadInformation.trafic_signals);
|
||||
|
||||
odp::LaneParser::Parse(road.child("lanes"), openDriveRoadInformation.lanes);
|
||||
odp::GeometryParser::Parse(road.child("planView"),
|
||||
openDriveRoadInformation.geometry_attributes);
|
||||
|
||||
out_open_drive_data.roads.emplace_back(std::move(openDriveRoadInformation));
|
||||
}
|
||||
|
||||
for (pugi::xml_node junction = xmlDoc.child("OpenDRIVE").child("junction");
|
||||
junction;
|
||||
junction = junction.next_sibling("junction")) {
|
||||
odp::JunctionParser::Parse(junction, out_open_drive_data.junctions);
|
||||
}
|
||||
|
||||
for (pugi::xml_node tlgroup = xmlDoc.child("OpenDRIVE").child("tlGroup");
|
||||
tlgroup;
|
||||
tlgroup = tlgroup.next_sibling("tlGroup")) {
|
||||
odp::TrafficGroupParser::Parse(tlgroup, out_open_drive_data.trafficlightgroups);
|
||||
}
|
||||
|
||||
for (pugi::xml_node trafficsigns = xmlDoc.child("OpenDRIVE").child("trafficsign");
|
||||
trafficsigns;
|
||||
trafficsigns = trafficsigns.next_sibling("trafficsign")) {
|
||||
odp::TrafficSignParser::Parse(trafficsigns, out_open_drive_data.trafficsigns);
|
||||
}
|
||||
|
||||
out_open_drive_data.geoReference = odp::GeoReferenceParser::Parse(
|
||||
xmlDoc.child("OpenDRIVE").child("header").child_value("geoReference"));
|
||||
|
||||
return true;
|
||||
}
|
|
@ -6,20 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "TrafficSignalsParser.h"
|
||||
#include "RoadLinkParser.h"
|
||||
#include "JunctionParser.h"
|
||||
|
||||
#include "ProfilesParser.h"
|
||||
#include "GeometryParser.h"
|
||||
#include "LaneParser.h"
|
||||
|
||||
#include "TrafficGroupParser.h"
|
||||
#include "TrafficSignParser.h"
|
||||
|
||||
#include "./pugixml/pugixml.hpp"
|
||||
|
||||
#include <iostream>
|
||||
#include "carla/opendrive/types.h"
|
||||
|
||||
enum class XmlInputType : int {
|
||||
FILE,
|
||||
|
@ -31,78 +18,5 @@ struct OpenDriveParser {
|
|||
const char *xml,
|
||||
carla::opendrive::types::OpenDriveData &out_open_drive_data,
|
||||
XmlInputType inputType,
|
||||
std::string *out_error = nullptr) {
|
||||
pugi::xml_document xmlDoc;
|
||||
pugi::xml_parse_result pugiParseResult;
|
||||
|
||||
switch (inputType) {
|
||||
case XmlInputType::FILE: {
|
||||
pugiParseResult = xmlDoc.load_file(xml);
|
||||
} break;
|
||||
|
||||
case XmlInputType::CONTENT: {
|
||||
pugiParseResult = xmlDoc.load_string(xml);
|
||||
} break;
|
||||
|
||||
default: {
|
||||
// TODO(Andrei): Log some kind of error
|
||||
return false;
|
||||
} break;
|
||||
}
|
||||
|
||||
if (pugiParseResult == false) {
|
||||
if (out_error != nullptr) {
|
||||
*out_error = pugiParseResult.description();
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
for (pugi::xml_node road = xmlDoc.child("OpenDRIVE").child("road");
|
||||
road;
|
||||
road = road.next_sibling("road")) {
|
||||
carla::opendrive::types::RoadInformation openDriveRoadInformation;
|
||||
|
||||
openDriveRoadInformation.attributes.name = road.attribute("name").value();
|
||||
openDriveRoadInformation.attributes.id = std::atoi(road.attribute("id").value());
|
||||
openDriveRoadInformation.attributes.length = std::stod(road.attribute("length").value());
|
||||
openDriveRoadInformation.attributes.junction = std::atoi(road.attribute("junction").value());
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
carla::opendrive::parser::ProfilesParser::Parse(road, openDriveRoadInformation.road_profiles);
|
||||
|
||||
carla::opendrive::parser::RoadLinkParser::Parse(road.child("link"), openDriveRoadInformation.road_link);
|
||||
carla::opendrive::parser::TrafficSignalsParser::Parse(road.child("signals"),
|
||||
openDriveRoadInformation.trafic_signals);
|
||||
|
||||
carla::opendrive::parser::LaneParser::Parse(road.child("lanes"), openDriveRoadInformation.lanes);
|
||||
carla::opendrive::parser::GeometryParser::Parse(road.child("planView"),
|
||||
openDriveRoadInformation.geometry_attributes);
|
||||
|
||||
out_open_drive_data.roads.emplace_back(std::move(openDriveRoadInformation));
|
||||
}
|
||||
|
||||
for (pugi::xml_node junction = xmlDoc.child("OpenDRIVE").child("junction");
|
||||
junction;
|
||||
junction = junction.next_sibling("junction")) {
|
||||
carla::opendrive::parser::JunctionParser::Parse(junction, out_open_drive_data.junctions);
|
||||
}
|
||||
|
||||
for (pugi::xml_node tlgroup = xmlDoc.child("OpenDRIVE").child("tlGroup");
|
||||
tlgroup;
|
||||
tlgroup = tlgroup.next_sibling("tlGroup")) {
|
||||
carla::opendrive::parser::TrafficGroupParser::Parse(tlgroup, out_open_drive_data.trafficlightgroups);
|
||||
}
|
||||
|
||||
for (pugi::xml_node trafficsigns = xmlDoc.child("OpenDRIVE").child("trafficsign");
|
||||
trafficsigns;
|
||||
trafficsigns = trafficsigns.next_sibling("trafficsign")) {
|
||||
carla::opendrive::parser::TrafficSignParser::Parse(trafficsigns, out_open_drive_data.trafficsigns);
|
||||
}
|
||||
|
||||
out_open_drive_data.geoReference = xmlDoc.child("OpenDRIVE").child("header").child_value("geoReference");
|
||||
|
||||
return true;
|
||||
}
|
||||
std::string *out_error = nullptr);
|
||||
};
|
||||
|
|
|
@ -6,6 +6,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
|
||||
#include <memory>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
@ -305,7 +307,7 @@ namespace types {
|
|||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
struct OpenDriveData {
|
||||
std::string geoReference;
|
||||
geom::GeoLocation geoReference;
|
||||
std::vector<RoadInformation> roads;
|
||||
std::vector<Junction> junctions;
|
||||
std::vector<TrafficLightGroup> trafficlightgroups;
|
||||
|
|
|
@ -23,7 +23,7 @@ namespace road {
|
|||
_map_data.SetJunctionInformation(junctionInfo);
|
||||
}
|
||||
|
||||
void SetGeoReference(const std::string &geoReference) {
|
||||
void SetGeoReference(const geom::GeoLocation &geoReference) {
|
||||
_map_data.SetGeoReference(geoReference);
|
||||
}
|
||||
|
||||
|
|
|
@ -53,7 +53,7 @@ namespace road {
|
|||
return _junction_information;
|
||||
}
|
||||
|
||||
const std::string &GetGeoReference() const {
|
||||
const geom::GeoLocation &GetGeoReference() const {
|
||||
return _geo_reference;
|
||||
}
|
||||
|
||||
|
@ -83,7 +83,7 @@ namespace road {
|
|||
_junction_information = junctionInfo;
|
||||
}
|
||||
|
||||
void SetGeoReference(const std::string &geoReference) {
|
||||
void SetGeoReference(const geom::GeoLocation &geoReference) {
|
||||
_geo_reference = geoReference;
|
||||
}
|
||||
|
||||
|
@ -95,7 +95,7 @@ namespace road {
|
|||
_traffic_signs = trafficSignData;
|
||||
}
|
||||
|
||||
std::string _geo_reference;
|
||||
geom::GeoLocation _geo_reference;
|
||||
|
||||
std::vector<lane_junction_t> _junction_information;
|
||||
|
||||
|
|
|
@ -5,49 +5,43 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "carla/road/element/LaneMarking.h"
|
||||
#include "carla/geom/GeoLocation.h"
|
||||
#include "carla/sensor/SensorData.h"
|
||||
|
||||
#include <vector>
|
||||
|
||||
namespace carla {
|
||||
namespace sensor {
|
||||
namespace data {
|
||||
|
||||
/// A change of gnss data
|
||||
/// A change of GNSS data.
|
||||
class GnssEvent : public SensorData {
|
||||
public:
|
||||
|
||||
explicit GnssEvent(
|
||||
size_t frame_number,
|
||||
const rpc::Transform &sensor_transform,
|
||||
double lat,
|
||||
double lon,
|
||||
double alt)
|
||||
const geom::GeoLocation &geo_location)
|
||||
: SensorData(frame_number, sensor_transform),
|
||||
_lat(std::move(lat)),
|
||||
_lon(std::move(lon)),
|
||||
_alt(std::move(alt)) {}
|
||||
_geo_location(geo_location) {}
|
||||
|
||||
const double &GetLatitude() const {
|
||||
return _lat;
|
||||
const geom::GeoLocation &GetGeoLocation() const {
|
||||
return _geo_location;
|
||||
}
|
||||
|
||||
const double &GetLongitude() const {
|
||||
return _lon;
|
||||
double GetLongitude() const {
|
||||
return _geo_location.longitude;
|
||||
}
|
||||
|
||||
const double &GetAltitude() const {
|
||||
return _alt;
|
||||
double GetLatitude() const {
|
||||
return _geo_location.latitude;
|
||||
}
|
||||
|
||||
double GetAltitude() const {
|
||||
return _geo_location.altitude;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
double _lat;
|
||||
|
||||
double _lon;
|
||||
|
||||
double _alt;
|
||||
geom::GeoLocation _geo_location;
|
||||
};
|
||||
|
||||
} // namespace data
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include <carla/geom/BoundingBox.h>
|
||||
#include <carla/geom/GeoLocation.h>
|
||||
#include <carla/geom/Location.h>
|
||||
#include <carla/geom/Rotation.h>
|
||||
#include <carla/geom/Transform.h>
|
||||
|
@ -68,6 +69,13 @@ namespace geom {
|
|||
return out;
|
||||
}
|
||||
|
||||
std::ostream &operator<<(std::ostream &out, const GeoLocation &geo_location) {
|
||||
out << "GeoLocation(latitude=" << geo_location.latitude
|
||||
<< ", longitude=" << geo_location.longitude
|
||||
<< ", altitude=" << geo_location.altitude << ')';
|
||||
return out;
|
||||
}
|
||||
|
||||
} // namespace geom
|
||||
} // namespace carla
|
||||
|
||||
|
@ -129,7 +137,7 @@ void export_geom() {
|
|||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
|
||||
class_<cg::Location, bases<cg::Vector3D>>("Location")
|
||||
class_<cg::Location, bases<cg::Vector3D>>("Location")
|
||||
.def(init<float, float, float>((arg("x")=0.0f, arg("y")=0.0f, arg("z")=0.0f)))
|
||||
.def(init<const cg::Vector3D &>((arg("rhs"))))
|
||||
.add_property("x", +[](const cg::Location &self) { return self.x; }, +[](cg::Location &self, float x) { self.x = x; })
|
||||
|
@ -177,4 +185,14 @@ class_<cg::Location, bases<cg::Vector3D>>("Location")
|
|||
.def("__ne__", &cg::BoundingBox::operator!=)
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
|
||||
class_<cg::GeoLocation>("GeoLocation")
|
||||
.def(init<double, double, double>((arg("latitude")=0.0, arg("longitude")=0.0, arg("altitude")=0.0)))
|
||||
.def_readwrite("latitude", &cg::GeoLocation::latitude)
|
||||
.def_readwrite("longitude", &cg::GeoLocation::longitude)
|
||||
.def_readwrite("altitude", &cg::GeoLocation::altitude)
|
||||
.def("__eq__", &cg::GeoLocation::operator==)
|
||||
.def("__ne__", &cg::GeoLocation::operator!=)
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
}
|
||||
|
|
|
@ -47,6 +47,12 @@ static auto GetTopology(const carla::client::Map &self) {
|
|||
return result;
|
||||
}
|
||||
|
||||
static carla::geom::GeoLocation ToGeolocation(
|
||||
const carla::client::Map &self,
|
||||
const carla::geom::Location &location) {
|
||||
return self.GetGeoReference().Transform(location);
|
||||
}
|
||||
|
||||
void export_map() {
|
||||
using namespace boost::python;
|
||||
namespace cc = carla::client;
|
||||
|
@ -58,6 +64,7 @@ void export_map() {
|
|||
.def("get_waypoint", &cc::Map::GetWaypoint, (arg("location"), arg("project_to_road")=true))
|
||||
.def("get_topology", &GetTopology)
|
||||
.def("generate_waypoints", CALL_RETURNING_LIST_1(cc::Map, GenerateWaypoints, double), (args("distance")))
|
||||
.def("transform_to_geolocation", &ToGeolocation, (arg("location")))
|
||||
.def("to_opendrive", CALL_RETURNING_COPY(cc::Map, GetOpenDrive))
|
||||
.def("save_to_disk", &SaveOpenDriveToDisk, (arg("path")=""))
|
||||
.def(self_ns::str(self_ns::self))
|
||||
|
|
|
@ -228,9 +228,9 @@ void export_sensor_data() {
|
|||
;
|
||||
|
||||
class_<csd::GnssEvent, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::GnssEvent>>("GnssEvent", no_init)
|
||||
.add_property("latitude", CALL_RETURNING_COPY(csd::GnssEvent, GetLatitude))
|
||||
.add_property("longitude", CALL_RETURNING_COPY(csd::GnssEvent, GetLongitude))
|
||||
.add_property("altitude", CALL_RETURNING_COPY(csd::GnssEvent, GetAltitude))
|
||||
.add_property("latitude", &csd::GnssEvent::GetLatitude)
|
||||
.add_property("longitude", &csd::GnssEvent::GetLongitude)
|
||||
.add_property("altitude", &csd::GnssEvent::GetAltitude)
|
||||
.def(self_ns::str(self_ns::self))
|
||||
;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue