Fix narrowing conversions and add warnings for it

This commit is contained in:
nsubiron 2019-04-23 20:29:12 +02:00
parent 4f3b000225
commit 75f1f8593b
48 changed files with 407 additions and 531 deletions

View File

@ -6,6 +6,8 @@
#pragma once
#include "carla/Debug.h"
#include <type_traits>
#include <iterator>
@ -19,13 +21,16 @@ namespace carla {
using iterator = IT;
using const_iterator = typename std::add_const<IT>::type;
using size_type = size_t;
using difference_type = typename std::iterator_traits<iterator>::difference_type;
using value_type = typename std::iterator_traits<iterator>::value_type;
using pointer = typename std::iterator_traits<iterator>::pointer;
using reference = typename std::iterator_traits<iterator>::reference;
explicit ListView(iterator begin, iterator end)
: _begin(begin), _end(end) {}
: _begin(begin), _end(end) {
DEBUG_ASSERT(std::distance(_begin, _end) >= 0);
}
ListView(const ListView &) = default;
ListView &operator=(const ListView &) = delete;
@ -58,8 +63,8 @@ namespace carla {
return _begin == _end;
}
difference_type size() const {
return std::distance(_begin, _end);
size_type size() const {
return static_cast<size_t>(std::distance(begin(), end()));
}
private:

View File

@ -98,14 +98,14 @@ namespace adaptor {
if (o.via.array.size != 2) {
::carla::throw_exception(clmdep_msgpack::type_error());
}
const auto index = o.via.array.ptr[0].as<int>();
const auto index = o.via.array.ptr[0].as<uint64_t>();
copy_to_variant(index, o, v, std::make_index_sequence<sizeof...(Ts)>());
return o;
}
private:
template <size_t I>
template <uint64_t I>
static void copy_to_variant_impl(
const clmdep_msgpack::object &o,
boost::variant<Ts...> &v) {
@ -115,9 +115,9 @@ namespace adaptor {
v = o.via.array.ptr[1].as<T>();
}
template <size_t... Is>
template <uint64_t... Is>
static void copy_to_variant(
const size_t index,
const uint64_t index,
const clmdep_msgpack::object &o,
boost::variant<Ts...> &v,
std::index_sequence<Is...>) {
@ -134,7 +134,7 @@ namespace adaptor {
clmdep_msgpack::packer<Stream> &o,
const boost::variant<Ts...> &v) const {
o.pack_array(2);
o.pack(static_cast<int>(v.which()));
o.pack(static_cast<uint64_t>(v.which()));
boost::apply_visitor([&](const auto &value) { o.pack(value); }, v);
return o;
}
@ -150,7 +150,7 @@ namespace adaptor {
o.via.array.ptr = static_cast<clmdep_msgpack::object*>(o.zone.allocate_align(
sizeof(clmdep_msgpack::object) * o.via.array.size,
MSGPACK_ZONE_ALIGNOF(clmdep_msgpack::object)));
o.via.array.ptr[0] = clmdep_msgpack::object(static_cast<int>(v.which()), o.zone);
o.via.array.ptr[0] = clmdep_msgpack::object(static_cast<uint64_t>(v.which()), o.zone);
boost::apply_visitor([&](const auto &value) {
o.via.array.ptr[1] = clmdep_msgpack::object(value, o.zone);
}, v);

View File

@ -7,6 +7,7 @@
#pragma once
#include <chrono>
#include <cstdint>
namespace carla {
namespace detail {
@ -35,8 +36,8 @@ namespace detail {
}
template <class RESOLUTION=std::chrono::milliseconds>
typename RESOLUTION::rep GetElapsedTime() const {
return std::chrono::duration_cast<RESOLUTION>(GetDuration()).count();
size_t GetElapsedTime() const {
return static_cast<size_t>(std::chrono::duration_cast<RESOLUTION>(GetDuration()).count());
}
bool IsRunning() const {

View File

@ -6,6 +6,8 @@
#pragma once
#include "carla/Debug.h"
#include <boost/date_time/posix_time/posix_time_types.hpp>
#include <chrono>
@ -29,7 +31,11 @@ namespace carla {
template <typename Rep, typename Period>
time_duration(std::chrono::duration<Rep, Period> duration)
: _milliseconds(std::chrono::duration_cast<std::chrono::milliseconds>(duration).count()) {}
: _milliseconds([=]() {
const auto count = std::chrono::duration_cast<std::chrono::milliseconds>(duration).count();
DEBUG_ASSERT(count >= 0);
return static_cast<size_t>(count);
}()) {}
time_duration(boost::posix_time::time_duration timeout)
: time_duration(std::chrono::milliseconds(timeout.total_milliseconds())) {}

View File

@ -57,7 +57,7 @@ namespace client {
(x < std::numeric_limits<float>::lowest())) {
LIBCARLA_THROW_INVALID_VALUE("float overflow");
}
return x;
return static_cast<float>(x);
}
template <>

View File

@ -51,7 +51,8 @@ namespace client {
/// @warning Linear complexity.
const_reference operator[](size_type pos) const {
return std::next(_blueprints.begin(), pos)->second;
using diff_t = std::iterator_traits<const_iterator>::difference_type;
return std::next(_blueprints.begin(), static_cast<diff_t>(pos))->second;
}
/// @warning Linear complexity.

View File

@ -19,7 +19,7 @@ namespace carla {
namespace client {
static geom::Location Rotate(float yaw, const geom::Location &location) {
yaw *= geom::Math::pi() / 180.0f;
yaw *= geom::Math::Pi<float>() / 180.0f;
const float c = std::cos(yaw);
const float s = std::sin(yaw);
return {

View File

@ -79,7 +79,7 @@ namespace detail {
time_duration GetTimeout() const {
auto timeout = rpc_client.get_timeout();
DEBUG_ASSERT(timeout.has_value());
return time_duration::milliseconds(*timeout);
return time_duration::milliseconds(static_cast<size_t>(*timeout));
}
const std::string endpoint;
@ -102,7 +102,7 @@ namespace detail {
Client::~Client() = default;
void Client::SetTimeout(time_duration timeout) {
_pimpl->rpc_client.set_timeout(timeout.milliseconds());
_pimpl->rpc_client.set_timeout(static_cast<int64_t>(timeout.milliseconds()));
}
time_duration Client::GetTimeout() const {

View File

@ -29,22 +29,22 @@ namespace geom {
/// @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));
return std::cos(Math::ToRadians(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));
mx = scale * Math::ToRadians(lon) * EARTH_RADIUS_EQUA;
my = scale * EARTH_RADIUS_EQUA * std::log(std::tan((90.0 + lat) * Math::Pi<double>() / 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;
lon = mx * 180.0 / (Math::Pi<double>() * EARTH_RADIUS_EQUA * scale);
lat = 360.0 * std::atan(std::exp(my / (EARTH_RADIUS_EQUA * scale))) / Math::Pi<double>() - 90.0;
}
/// Adds meters dx/dy to given lat/lon and returns new lat/lon.

View File

@ -33,7 +33,7 @@ namespace geom {
// -- Other methods --------------------------------------------------------
// =========================================================================
double Distance(const Location &loc) const {
auto Distance(const Location &loc) const {
return Math::Distance(*this, loc);
}
@ -62,17 +62,17 @@ namespace geom {
}
/// @todo Do we need to multiply locations?
Location &operator*=(const double &rhs) {
Location &operator*=(float rhs) {
static_cast<Vector3D &>(*this) *= rhs;
return *this;
}
friend Location operator*(Location lhs, double rhs) {
friend Location operator*(Location lhs, float rhs) {
lhs *= rhs;
return lhs;
}
friend Location operator*(double lhs, Location rhs) {
friend Location operator*(float lhs, Location rhs) {
rhs *= lhs;
return rhs;
}

View File

@ -11,44 +11,27 @@
namespace carla {
namespace geom {
/// Returns a pair containing:
/// - @b first: distance from v to p' where p' = p projected on segment (w -
/// v)
/// - @b second: Euclidean distance from p to p'
/// @param p point to calculate distance
/// @param v first point of the segment
/// @param w second point of the segment
std::pair<double, double> Math::DistSegmentPoint(
std::pair<float, float> Math::DistanceSegmentToPoint(
const Vector3D &p,
const Vector3D &v,
const Vector3D &w) {
const double l2 = DistanceSquared2D(v, w);
const double l = std::sqrt(l2);
if (l2 == 0.0) {
return std::make_pair(0.0, Distance2D(v, p));
const float l2 = DistanceSquared2D(v, w);
const float l = std::sqrt(l2);
if (l2 == 0.0f) {
return std::make_pair(0.0f, Distance2D(v, p));
}
const double dot_p_w = Dot2D(p - v, w - v);
const double t = clamp01(dot_p_w / l2);
const float dot_p_w = Dot2D(p - v, w - v);
const float t = Clamp(dot_p_w / l2);
const Vector3D projection = v + t * (w - v);
return std::make_pair(t * l, Distance2D(projection, p));
}
Vector3D Math::RotatePointOnOrigin2D(Vector3D p, double angle) {
double s = std::sin(angle);
double c = std::cos(angle);
return Vector3D(p.x * c - p.y * s, p.x * s + p.y * c, 0.0);
}
/// Returns a pair containing:
/// - @b first: distance across the arc from start_pos to p' where p' = p
/// projected on Arc
/// - @b second: Euclidean distance from p to p'
std::pair<double, double> Math::DistArcPoint(
std::pair<float, float> Math::DistanceArcToPoint(
Vector3D p,
Vector3D start_pos,
double length,
double heading, // [radians]
double curvature) {
const float length,
float heading, // [radians]
float curvature) {
/// @todo: Because Unreal's coordinates, hacky way to correct
/// the -y, this must be changed in the future
@ -61,7 +44,7 @@ namespace geom {
// and we are only calculating distances, we can invert the y
// axis (along with the curvature and the heading), so if the
// curvature is negative, the algorithm will work as expected
if (curvature < 0.0) {
if (curvature < 0.0f) {
p.y = -p.y;
start_pos.y = -start_pos.y;
heading = -heading;
@ -71,13 +54,13 @@ namespace geom {
// transport point relative to the arc starting poistion and rotation
const Vector3D rotated_p(RotatePointOnOrigin2D(p - start_pos, -heading));
const double radius = 1.0 / curvature;
const Vector3D circ_center(0, radius, 0);
const float radius = 1.0f / curvature;
const Vector3D circ_center(0.0f, radius, 0.0f);
// check if the point is in the center of the circle, so we know p
// is in the same distance of every possible point in the arc
if (rotated_p == circ_center) {
return std::make_pair(0.0, radius);
return std::make_pair(0.0f, radius);
}
// find intersection position using the unit vector from the center
@ -88,18 +71,20 @@ namespace geom {
// circumference of a circle = 2 * PI * r
// last_point_angle = (length / circumference) * 2 * PI
// so last_point_angle = length / radius
const double last_point_angle = length / radius;
const float last_point_angle = length / radius;
constexpr float pi_half = Pi<float>() / 2.0f;
// move the point relative to the center of the circle and find
// the angle between the point and the center of coords in rad
double angle = std::atan2(intersection.y - radius, intersection.x) + pi_half();
float angle = std::atan2(intersection.y - radius, intersection.x) + pi_half;
if (angle < 0.0) {
angle += pi_double();
if (angle < 0.0f) {
angle += Pi<float>() * 2.0f;
}
// see if the angle is between 0 and last_point_angle
DEBUG_ASSERT(angle >= 0.0);
DEBUG_ASSERT(angle >= 0.0f);
if (angle <= last_point_angle) {
return std::make_pair(
angle * radius,
@ -107,34 +92,29 @@ namespace geom {
}
// find the nearest point, start or end to intersection
const double start_dist = Distance2D(Vector3D(), rotated_p);
const float start_dist = Distance2D(Vector3D(), rotated_p);
const Vector3D end_pos(
radius * std::cos(last_point_angle - pi_half()),
radius *std::sin(last_point_angle - pi_half()) + circ_center.y,
0.0);
const double end_dist = Distance2D(end_pos, rotated_p);
radius * std::cos(last_point_angle - pi_half),
radius * std::sin(last_point_angle - pi_half) + circ_center.y,
0.0f);
const float end_dist = Distance2D(end_pos, rotated_p);
return (start_dist < end_dist) ?
std::make_pair(0.0, start_dist) :
std::make_pair(0.0f, start_dist) :
std::make_pair(length, end_dist);
}
bool Math::PointInRectangle(
const Vector3D &pos,
const Vector3D &extent,
double angle, // [radians]
const Vector3D &p) {
// Move p relative to pos's position and angle
Vector3D transf_p = RotatePointOnOrigin2D(p - pos, -angle);
return transf_p.x <= extent.x && transf_p.y <= extent.y &&
transf_p.x >= -extent.x && transf_p.y >= -extent.y;
Vector3D Math::RotatePointOnOrigin2D(Vector3D p, float angle) {
const float s = std::sin(angle);
const float c = std::cos(angle);
return Vector3D(p.x * c - p.y * s, p.x * s + p.y * c, 0.0f);
}
Vector3D Math::GetForwardVector(const Rotation &rotation) {
const float cp = std::cos(to_radians(rotation.pitch));
const float sp = std::sin(to_radians(rotation.pitch));
const float cy = std::cos(to_radians(rotation.yaw));
const float sy = std::sin(to_radians(rotation.yaw));
const float cp = std::cos(ToRadians(rotation.pitch));
const float sp = std::sin(ToRadians(rotation.pitch));
const float cy = std::cos(ToRadians(rotation.yaw));
const float sy = std::sin(ToRadians(rotation.yaw));
return {cy * cp, sy * cp, sp};
}

View File

@ -9,8 +9,9 @@
#include "carla/Debug.h"
#include "carla/geom/Vector3D.h"
#include <utility>
#include <cmath>
#include <type_traits>
#include <utility>
namespace carla {
namespace geom {
@ -20,41 +21,31 @@ namespace geom {
class Math {
public:
static constexpr auto pi() {
return 3.14159265358979323846264338327950288;
}
static constexpr auto pi_double() {
return 2.0 * pi();
}
static constexpr auto pi_half() {
return 0.5 * pi();
}
static constexpr auto to_degrees(double rad) {
return rad * (180.0 / pi());
}
static constexpr auto to_radians(double deg) {
return deg * (pi() / 180.0);
template <typename T>
static constexpr T Pi() {
static_assert(std::is_floating_point<T>::value, "type must be floating point");
return static_cast<T>(3.14159265358979323846264338327950288);
}
template <typename T>
static T clamp(
const T &a,
const T &min,
const T &max) {
static constexpr T ToDegrees(T rad) {
static_assert(std::is_floating_point<T>::value, "type must be floating point");
return rad * (T(180.0) / Pi<T>());
}
template <typename T>
static constexpr T ToRadians(T deg) {
static_assert(std::is_floating_point<T>::value, "type must be floating point");
return deg * (Pi<T>() / T(180.0));
}
template <typename T>
static T Clamp(T a, T min = T(0), T max = T(1)) {
return std::min(std::max(a, min), max);
}
template <typename T>
static T clamp01(T a) {
return clamp(a, 0.0, 1.0);
}
template <typename T>
static T sqr(const T &a) {
static T Square(const T &a) {
return a * a;
}
@ -67,11 +58,11 @@ namespace geom {
}
static auto DistanceSquared(const Vector3D &a, const Vector3D &b) {
return sqr(b.x - a.x) + sqr(b.y - a.y) + sqr(b.z - a.z);
return Square(b.x - a.x) + Square(b.y - a.y) + Square(b.z - a.z);
}
static auto DistanceSquared2D(const Vector3D &a, const Vector3D &b) {
return sqr(b.x - a.x) + sqr(b.y - a.y);
return Square(b.x - a.x) + Square(b.y - a.y);
}
static auto Distance(const Vector3D &a, const Vector3D &b) {
@ -82,25 +73,30 @@ namespace geom {
return std::sqrt(DistanceSquared2D(a, b));
}
static std::pair<double, double> DistSegmentPoint(
const Vector3D &,
const Vector3D &,
const Vector3D &);
/// Returns a pair containing:
/// - @b first: distance from v to p' where p' = p projected on segment
/// (w - v)
/// - @b second: Euclidean distance from p to p'
/// @param p point to calculate distance
/// @param v first point of the segment
/// @param w second point of the segment
static std::pair<float, float> DistanceSegmentToPoint(
const Vector3D &p,
const Vector3D &v,
const Vector3D &w);
static Vector3D RotatePointOnOrigin2D(Vector3D p, double angle);
/// Returns a pair containing:
/// - @b first: distance across the arc from start_pos to p' where p' = p
/// projected on Arc
/// - @b second: Euclidean distance from p to p'
static std::pair<float, float> DistanceArcToPoint(
Vector3D p,
Vector3D start_pos,
float length,
float heading, // [radians]
float curvature);
static std::pair<double, double> DistArcPoint(
Vector3D,
Vector3D,
double,
double, // [radians]
double);
static bool PointInRectangle(
const Vector3D &,
const Vector3D &,
double, // [radians]
const Vector3D &);
static Vector3D RotatePointOnOrigin2D(Vector3D p, float angle);
/// Compute the unit vector pointing towards the X-axis of @a rotation.
static Vector3D GetForwardVector(const Rotation &rotation);

View File

@ -55,12 +55,12 @@ namespace geom {
void TransformPoint(Vector3D &in_point) const {
// Rotate
double cy = cos(Math::to_radians(rotation.yaw));
double sy = sin(Math::to_radians(rotation.yaw));
double cr = cos(Math::to_radians(rotation.roll));
double sr = sin(Math::to_radians(rotation.roll));
double cp = cos(Math::to_radians(rotation.pitch));
double sp = sin(Math::to_radians(rotation.pitch));
const float cy = std::cos(Math::ToRadians(rotation.yaw));
const float sy = std::sin(Math::ToRadians(rotation.yaw));
const float cr = std::cos(Math::ToRadians(rotation.roll));
const float sr = std::sin(Math::ToRadians(rotation.roll));
const float cp = std::cos(Math::ToRadians(rotation.pitch));
const float sp = std::sin(Math::ToRadians(rotation.pitch));
Vector3D out_point;
out_point.x = in_point.x * (cp * cy) +

View File

@ -39,18 +39,18 @@ namespace geom {
// -- Other methods --------------------------------------------------------
// =========================================================================
double SquaredLength() const {
float SquaredLength() const {
return x * x + y * y;
}
double Length() const {
float Length() const {
return std::sqrt(SquaredLength());
}
Vector2D MakeUnitVector() const {
const double len = Length();
DEBUG_ASSERT(len > std::numeric_limits<double>::epsilon());
double k = 1.0 / len;
const float len = Length();
DEBUG_ASSERT(len > 2.0f * std::numeric_limits<float>::epsilon());
const float k = 1.0f / len;
return Vector2D(x * k, y * k);
}
@ -80,34 +80,34 @@ namespace geom {
return lhs;
}
Vector2D &operator*=(const double &rhs) {
Vector2D &operator*=(float rhs) {
x *= rhs;
y *= rhs;
return *this;
}
friend Vector2D operator*(Vector2D lhs, const double &rhs) {
friend Vector2D operator*(Vector2D lhs, float rhs) {
lhs *= rhs;
return lhs;
}
friend Vector2D operator*(const double &lhs, Vector2D rhs) {
friend Vector2D operator*(float lhs, Vector2D rhs) {
rhs *= lhs;
return rhs;
}
Vector2D &operator/=(const double &rhs) {
Vector2D &operator/=(float rhs) {
x /= rhs;
y /= rhs;
return *this;
}
friend Vector2D operator/(Vector2D lhs, const double &rhs) {
friend Vector2D operator/(Vector2D lhs, float rhs) {
lhs /= rhs;
return lhs;
}
friend Vector2D operator/(const double &lhs, Vector2D rhs) {
friend Vector2D operator/(float lhs, Vector2D rhs) {
rhs /= lhs;
return rhs;
}

View File

@ -42,18 +42,18 @@ namespace geom {
// -- Other methods --------------------------------------------------------
// =========================================================================
double SquaredLength() const {
float SquaredLength() const {
return x * x + y * y + z * z;
}
double Length() const {
float Length() const {
return std::sqrt(SquaredLength());
}
Vector3D MakeUnitVector() const {
const double len = Length();
DEBUG_ASSERT(len > std::numeric_limits<double>::epsilon());
double k = 1.0 / len;
const float length = Length();
DEBUG_ASSERT(length > 2.0f * std::numeric_limits<float>::epsilon());
const float k = 1.0f / length;
return Vector3D(x * k, y * k, z * k);
}
@ -85,36 +85,36 @@ namespace geom {
return lhs;
}
Vector3D &operator*=(const double &rhs) {
Vector3D &operator*=(float rhs) {
x *= rhs;
y *= rhs;
z *= rhs;
return *this;
}
friend Vector3D operator*(Vector3D lhs, const double &rhs) {
friend Vector3D operator*(Vector3D lhs, float rhs) {
lhs *= rhs;
return lhs;
}
friend Vector3D operator*(const double &lhs, Vector3D rhs) {
friend Vector3D operator*(float lhs, Vector3D rhs) {
rhs *= lhs;
return rhs;
}
Vector3D &operator/=(const double &rhs) {
Vector3D &operator/=(float rhs) {
x /= rhs;
y /= rhs;
z /= rhs;
return *this;
}
friend Vector3D operator/(Vector3D lhs, const double &rhs) {
friend Vector3D operator/(Vector3D lhs, float rhs) {
lhs /= rhs;
return lhs;
}
friend Vector3D operator/(const double &lhs, Vector3D rhs) {
friend Vector3D operator/(float lhs, Vector3D rhs) {
rhs /= lhs;
return rhs;
}
@ -140,14 +140,14 @@ namespace geom {
Vector3D(const FVector &vector)
: Vector3D(vector.X, vector.Y, vector.Z) {}
Vector3D &ToMeters(void) { // from centimeters to meters.
Vector3D &ToMeters() { // from centimeters to meters.
x *= 0.001f;
y *= 0.001f;
z *= 0.001f;
return *this;
}
Vector3D &ToCentimeters(void) { // from meters to centimeters.
Vector3D &ToCentimeters() { // from meters to centimeters.
x *= 100.0f;
y *= 100.0f;
z *= 100.0f;

View File

@ -14,7 +14,7 @@ namespace carla {
namespace opendrive {
namespace parser {
using RoadId = int;
using RoadId = road::RoadId;
struct GeometryArc {
double curvature { 0.0 };
@ -45,7 +45,7 @@ namespace parser {
};
struct Geometry {
RoadId road_id { -1 };
RoadId road_id { 0u };
double s { 0.0 };
double x { 0.0 };
double y { 0.0 };
@ -74,7 +74,7 @@ namespace parser {
Geometry geo;
// get road id
geo.road_id = node_road.attribute("id").as_int();
geo.road_id = node_road.attribute("id").as_uint();
// get common properties
geo.s = node_geo.attribute("s").as_double();

View File

@ -49,9 +49,9 @@ namespace parser {
for (pugi::xml_node connection_node : junction_node.children("connection")) {
Connection connection;
connection.id = connection_node.attribute("id").as_int();
connection.incoming_road = connection_node.attribute("incomingRoad").as_int();
connection.connecting_road = connection_node.attribute("connectingRoad").as_int();
connection.id = connection_node.attribute("id").as_uint();
connection.incoming_road = connection_node.attribute("incomingRoad").as_uint();
connection.connecting_road = connection_node.attribute("connectingRoad").as_uint();
// Lane Links
for (pugi::xml_node lane_link_node : connection_node.children("laneLink")) {
@ -73,7 +73,8 @@ namespace parser {
for (auto &junction : junctions) {
map_builder.AddJunction(junction.id, junction.name);
for (auto &connection : junction.connections) {
map_builder.AddConnection(junction.id,
map_builder.AddConnection(
junction.id,
connection.id,
connection.incoming_road,
connection.connecting_road);

View File

@ -185,7 +185,7 @@ namespace parser {
// Lanes
for (pugi::xml_node road_node : open_drive_node.children("road")) {
road::RoadId road_id = road_node.attribute("id").as_int();
road::RoadId road_id = road_node.attribute("id").as_uint();
for (pugi::xml_node lanes_node : road_node.children("lanes")) {

View File

@ -60,7 +60,7 @@ namespace parser {
ElevationProfile elev;
// get road id
road::RoadId road_id = node_road.attribute("id").as_int();
road::RoadId road_id = node_road.attribute("id").as_uint();
elev.road = map_builder.GetRoad(road_id);
// get common properties
@ -82,7 +82,7 @@ namespace parser {
LateralProfile lateral;
// get road id
road::RoadId road_id = node_road.attribute("id").as_int();
road::RoadId road_id = node_road.attribute("id").as_uint();
lateral.road = map_builder.GetRoad(road_id);
// get common properties

View File

@ -119,7 +119,7 @@ namespace parser {
Road road { 0, "", 0.0, -1, 0, 0, {}, {}, {} };
// attributes
road.id = node_road.attribute("id").as_int();
road.id = node_road.attribute("id").as_uint();
road.name = node_road.attribute("name").value();
road.length = node_road.attribute("length").as_double();
road.junction_id = node_road.attribute("junction").as_int();
@ -128,10 +128,10 @@ namespace parser {
pugi::xml_node link = node_road.child("link");
if (link) {
if (link.child("predecessor")) {
road.predecessor = link.child("predecessor").attribute("elementId").as_int();
road.predecessor = link.child("predecessor").attribute("elementId").as_uint();
}
if (link.child("successor")) {
road.successor = link.child("successor").attribute("elementId").as_int();
road.successor = link.child("successor").attribute("elementId").as_uint();
}
}

View File

@ -28,8 +28,8 @@ namespace parser {
for (pugi::xml_node validity_node = parent_node.child(node_name.c_str());
validity_node;
validity_node = validity_node.next_sibling("validity")) {
const int from_lane = validity_node.attribute("fromLane").as_int();
const int to_lane = validity_node.attribute("toLane").as_int();
const auto from_lane = static_cast<int16_t>(validity_node.attribute("fromLane").as_int());
const auto to_lane = static_cast<int16_t>(validity_node.attribute("toLane").as_int());
log_debug("Added validity to signal ", signalID, ":", from_lane, to_lane);
function(roadID, signalID, from_lane, to_lane);
}
@ -108,15 +108,14 @@ namespace parser {
pitch,
roll);
AddValidity(signal_node, "validity", road_id, signal_id,
([&map_builder](const RoadID roadID, const SignalID &signal_id, const int16_t from_lane,
const int16_t to_lane)
{ map_builder.AddValidityToSignal(roadID, signal_id, from_lane, to_lane);
([&map_builder](auto &&... args)
{ map_builder.AddValidityToSignal(args...);
}));
for (pugi::xml_node dependency_node = signal_node.child("dependency");
dependency_node;
dependency_node = dependency_node.next_sibling("validity")) {
const DependencyID dependency_id = dependency_node.attribute("id").as_int();
const DependencyID dependency_id = dependency_node.attribute("id").as_uint();
const std::string dependency_type = dependency_node.attribute("type").value();
log_debug("Added dependency to signal ", signal_id, ":", dependency_id, dependency_type);
map_builder.AddDependencyToSignal(road_id, signal_id, dependency_id, dependency_type);
@ -127,7 +126,7 @@ namespace parser {
signalreference_node = signalreference_node.next_sibling("signalReference")) {
const double s_position = signalreference_node.attribute("s").as_double();
const double t_position = signalreference_node.attribute("t").as_double();
const SignalID signal_reference_id = signalreference_node.attribute("id").as_int();
const SignalID signal_reference_id = signalreference_node.attribute("id").as_uint();
const std::string signal_reference_orientation =
signalreference_node.attribute("orientation").value();
log_debug("Road: ",

View File

@ -25,31 +25,31 @@ namespace parser {
*/
void TrafficGroupParser::Parse(
const pugi::xml_document &xml,
const pugi::xml_document & /*xml*/,
carla::road::MapBuilder & /* map_builder */) {
pugi::xml_node opendrive_node = xml.child("OpenDRIVE");
for (pugi::xml_node userdata_node = opendrive_node.child("userData");
userdata_node;
userdata_node = userdata_node.next_sibling("userData")) {
for (pugi::xml_node trafficgroup_node = userdata_node.child("trafficGroup");
trafficgroup_node;
trafficgroup_node = trafficgroup_node.next_sibling("trafficGroup")) {
uint16_t id = trafficgroup_node.attribute("id").as_int(0);
uint16_t redTime = trafficgroup_node.attribute("redTime").as_int(0);
uint16_t yellowTime = trafficgroup_node.attribute("yellowTime").as_int(0);
uint16_t greenTime = trafficgroup_node.attribute("greenTime").as_int(0);
log_debug("Found TrafficGroup with ID: ",
id,
"Times (",
redTime,
", ",
yellowTime,
", ",
greenTime,
")");
}
// map_builder.AddTrafficGroup(id, redTime, yellowTime, greenTime);
}
// pugi::xml_node opendrive_node = xml.child("OpenDRIVE");
// for (pugi::xml_node userdata_node = opendrive_node.child("userData");
// userdata_node;
// userdata_node = userdata_node.next_sibling("userData")) {
// for (pugi::xml_node trafficgroup_node = userdata_node.child("trafficGroup");
// trafficgroup_node;
// trafficgroup_node = trafficgroup_node.next_sibling("trafficGroup")) {
// uint16_t id = trafficgroup_node.attribute("id").as_int(0);
// uint16_t redTime = trafficgroup_node.attribute("redTime").as_int(0);
// uint16_t yellowTime = trafficgroup_node.attribute("yellowTime").as_int(0);
// uint16_t greenTime = trafficgroup_node.attribute("greenTime").as_int(0);
// log_debug("Found TrafficGroup with ID: ",
// id,
// "Times (",
// redTime,
// ", ",
// yellowTime,
// ", ",
// greenTime,
// ")");
// }
// map_builder.AddTrafficGroup(id, redTime, yellowTime, greenTime);
// }
}
} // namespace parser

View File

@ -40,6 +40,12 @@
// For placement new
#include <new>
#if defined(__clang__)
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wconversion"
# pragma clang diagnostic ignored "-Wdouble-promotion"
#endif
#ifdef _MSC_VER
# pragma warning(push)
# pragma warning(disable: 4127) // conditional expression is constant
@ -12737,6 +12743,10 @@ namespace pugi
# pragma clang diagnostic pop
#endif
#if defined(__clang__)
# pragma clang diagnostic pop
#endif
// Undefine all local macros (makes sure we're not leaking macros in header-only mode)
#undef PUGI__NO_INLINE
#undef PUGI__UNLIKELY

View File

@ -19,7 +19,8 @@ namespace pointcloud {
template <typename PointIt>
static void Dump(std::ostream &out, PointIt begin, PointIt end) {
WriteHeader(out, std::distance(begin, end));
DEBUG_ASSERT(std::distance(begin, end) >= 0);
WriteHeader(out, static_cast<size_t>(std::distance(begin, end)));
for (; begin != end; ++begin) {
out << begin->x << ' ' << begin->y << ' ' << begin->z << '\n';
}

View File

@ -14,6 +14,7 @@
#include "carla/StopWatch.h"
#include <algorithm>
#include <limits>
#include <string>
namespace carla {
@ -30,8 +31,7 @@ namespace detail {
~ProfilerData();
void Annotate(const StopWatch &stop_watch) {
const size_t elapsed_microseconds =
stop_watch.GetElapsedTime<std::chrono::microseconds>();
const auto elapsed_microseconds = stop_watch.GetElapsedTime<std::chrono::microseconds>();
++_count;
_total_microseconds += elapsed_microseconds;
_max_elapsed = std::max(elapsed_microseconds, _max_elapsed);
@ -70,7 +70,7 @@ namespace detail {
size_t _max_elapsed = 0u;
size_t _min_elapsed = -1;
size_t _min_elapsed = std::numeric_limits<size_t>::max();
};
class ScopedProfiler {

View File

@ -146,11 +146,10 @@ namespace road {
uint32_t lane_type) const {
// max_nearests represents the max nearests roads
// where we will search for nearests lanes
constexpr int max_nearests = 50;
constexpr size_t max_nearests = 50u;
// in case that map has less than max_nearests lanes,
// we will use the maximum lanes
const int max_nearest_allowed = _data.GetRoadCount() < max_nearests ?
_data.GetRoadCount() : max_nearests;
const size_t max_nearest_allowed = std::min(_data.GetRoadCount(), max_nearests);
// Unreal's Y axis hack
const auto pos_inverted_y = geom::Location(pos.x, -pos.y, pos.z);
@ -169,10 +168,11 @@ namespace road {
const auto road = &road_pair.second;
const auto current_dist = road->GetNearestPoint(pos_inverted_y);
for (int i = 0; i < max_nearest_allowed; ++i) {
for (size_t i = 0u; i < max_nearest_allowed; ++i) {
if (current_dist.second < nearest_dist[i]) {
// reorder nearest_dist
for (int j = max_nearest_allowed - 1; j > i; --j) {
for (size_t j = max_nearest_allowed - 1u; j > i; --j) {
DEBUG_ASSERT(j > 0u);
nearest_dist[j] = nearest_dist[j - 1];
ids[j] = ids[j - 1];
dists[j] = dists[j - 1];
@ -188,7 +188,7 @@ namespace road {
// search for the nearest lane in nearest_dist
Waypoint waypoint;
auto nearest_lane_dist = std::numeric_limits<double>::max();
for (int i = 0; i < max_nearest_allowed; ++i) {
for (size_t i = 0u; i < max_nearest_allowed; ++i) {
auto lane_dist = _data.GetRoad(ids[i]).GetNearestLane(dists[i], pos_inverted_y, lane_type);
if (lane_dist.second < nearest_lane_dist) {
@ -208,7 +208,7 @@ namespace road {
// Make sure 0.0 < waipoint.s < Road's length
constexpr double margin = 5.0 * EPSILON;
DEBUG_ASSERT(margin < road.GetLength() - margin);
waypoint.s = geom::Math::clamp<double>(waypoint.s, margin, road.GetLength() - margin);
waypoint.s = geom::Math::Clamp(waypoint.s, margin, road.GetLength() - margin);
auto &lane = road.GetLaneByDistance(waypoint.s, waypoint.lane_id);
@ -291,17 +291,17 @@ namespace road {
lane_tangent *= -1;
geom::Rotation rot(
geom::Math::to_degrees(dp.pitch),
geom::Math::to_degrees(-dp.tangent), // Unreal's Y axis hack
0.0);
geom::Math::ToDegrees(static_cast<float>(dp.pitch)),
geom::Math::ToDegrees(-static_cast<float>(dp.tangent)), // Unreal's Y axis hack
0.0f);
dp.ApplyLateralOffset(lane_width);
if (waypoint.lane_id > 0) {
rot.yaw += 180.0 + geom::Math::to_degrees(lane_tangent);
rot.pitch = 360.0 - rot.pitch;
rot.yaw += 180.0f + geom::Math::ToDegrees(lane_tangent);
rot.pitch = 360.0f - rot.pitch;
} else {
rot.yaw -= geom::Math::to_degrees(lane_tangent);
rot.yaw -= geom::Math::ToDegrees(lane_tangent);
}
// Unreal's Y axis hack

View File

@ -243,12 +243,12 @@ namespace road {
// build road objects
carla::road::Road *MapBuilder::AddRoad(
const uint32_t road_id,
const RoadId road_id,
const std::string name,
const double length,
const int32_t junction_id,
const int32_t predecessor,
const int32_t successor) {
const JuncId junction_id,
const RoadId predecessor,
const RoadId successor) {
// add it
auto road = &(_map_data._roads.emplace(road_id, Road()).first->second);
@ -307,11 +307,12 @@ namespace road {
const double hdg,
const double length) {
DEBUG_ASSERT(road != nullptr);
auto line_geometry = std::make_unique<GeometryLine>(s,
const geom::Location location(static_cast<float>(x), static_cast<float>(y), 0.0f);
auto line_geometry = std::make_unique<GeometryLine>(
s,
length,
hdg,
geom::Location(x, y, 0.0));
location);
_temp_road_info_container[road].emplace_back(std::unique_ptr<RoadInfo>(new RoadInfoGeometry(s,
std::move(line_geometry))));
@ -347,11 +348,12 @@ namespace road {
const double length,
const double curvature) {
DEBUG_ASSERT(road != nullptr);
auto arc_geometry = std::make_unique<GeometryArc>(s,
const geom::Location location(static_cast<float>(x), static_cast<float>(y), 0.0f);
auto arc_geometry = std::make_unique<GeometryArc>(
s,
length,
hdg,
geom::Location(x, y, 0.0),
location,
curvature);
_temp_road_info_container[road].emplace_back(std::unique_ptr<RoadInfo>(new RoadInfoGeometry(s,
@ -408,20 +410,20 @@ namespace road {
}
void MapBuilder::AddConnection(
const int32_t junction_id,
const int32_t connection_id,
const int32_t incoming_road,
const int32_t connecting_road) {
const JuncId junction_id,
const ConId connection_id,
const RoadId incoming_road,
const RoadId connecting_road) {
DEBUG_ASSERT(_map_data.GetJunction(junction_id) != nullptr);
_map_data.GetJunction(junction_id)->GetConnections().emplace(connection_id,
Junction::Connection(connection_id, incoming_road, connecting_road));
}
void MapBuilder::AddLaneLink(
const int32_t junction_id,
const int32_t connection_id,
const int32_t from,
const int32_t to) {
const JuncId junction_id,
const ConId connection_id,
const LaneId from,
const LaneId to) {
DEBUG_ASSERT(_map_data.GetJunction(junction_id) != nullptr);
_map_data.GetJunction(junction_id)->GetConnection(connection_id)->AddLaneLink(from, to);
}
@ -459,8 +461,8 @@ namespace road {
}
void MapBuilder::AddDependencyToSignal(
const uint32_t road_id,
const uint32_t signal_id,
const RoadId road_id,
const SignId signal_id,
const uint32_t dependency_id,
const std::string dependency_type) {
DEBUG_ASSERT(_map_data.GetRoad(road_id).GetSignal(signal_id) != nullptr);
@ -506,7 +508,10 @@ namespace road {
// return a list of pointers to all lanes from a lane (using road and junction
// info)
std::vector<Lane *> MapBuilder::GetLaneNext(RoadId road_id, int section_id, LaneId lane_id) {
std::vector<Lane *> MapBuilder::GetLaneNext(
RoadId road_id,
SectionId section_id,
LaneId lane_id) {
std::vector<Lane *> result;
if (!_map_data.ContainsRoad(road_id)) {
@ -556,7 +561,11 @@ namespace road {
}
} else {
// several roads (junction)
auto options = GetJunctionLanes(next_road, road_id, lane_id);
/// @todo Is it correct to use a road id as section id? (NS: I just added
/// this cast to avoid compiler warnings).
auto next_road_as_junction = static_cast<JuncId>(next_road);
auto options = GetJunctionLanes(next_road_as_junction, road_id, lane_id);
for (auto opt : options) {
result.push_back(GetEdgeLanePointer(opt.first, (opt.second <= 0), opt.second));
}
@ -566,7 +575,7 @@ namespace road {
}
std::vector<std::pair<RoadId, LaneId>> MapBuilder::GetJunctionLanes(
RoadId junction_id,
JuncId junction_id,
RoadId road_id,
LaneId lane_id) {
std::vector<std::pair<RoadId, LaneId>> result;

View File

@ -22,12 +22,12 @@ namespace road {
// called from road parser
carla::road::Road *AddRoad(
const uint32_t road_id,
const RoadId road_id,
const std::string name,
const double length,
const int32_t junction_id,
const int32_t predecessor,
const int32_t successor);
const JuncId junction_id,
const RoadId predecessor,
const RoadId successor);
carla::road::LaneSection *AddRoadSection(
carla::road::Road *road,
@ -36,11 +36,11 @@ namespace road {
carla::road::Lane *AddRoadSectionLane(
carla::road::LaneSection *section,
const int32_t lane_id,
const LaneId lane_id,
const uint32_t lane_type,
const bool lane_level,
const int32_t predecessor,
const int32_t successor);
const LaneId predecessor,
const LaneId successor);
// called from geometry parser
void AddRoadGeometryLine(
@ -136,8 +136,8 @@ namespace road {
// Signal methods
void AddSignal(
const uint32_t road_id,
const uint32_t signal_id,
const RoadId road_id,
const SignId signal_id,
const double s,
const double t,
const std::string name,
@ -157,29 +157,31 @@ namespace road {
const double roll);
void AddValidityToLastAddedSignal(
const uint32_t road_id,
const uint32_t signal_id,
const int32_t from_lane,
const int32_t to_lane);
const RoadId road_id,
const SignId signal_id,
const LaneId from_lane,
const LaneId to_lane);
// called from junction parser
void AddJunction(const int32_t id, const std::string name);
void AddJunction(
const JuncId id,
const std::string name);
void AddConnection(
const int32_t junction_id,
const int32_t connection_id,
const int32_t incoming_road,
const int32_t connecting_road);
const JuncId junction_id,
const ConId connection_id,
const RoadId incoming_road,
const RoadId connecting_road);
void AddLaneLink(
const int32_t junction_id,
const int32_t connection_id,
const int32_t from,
const int32_t to);
const JuncId junction_id,
const ConId connection_id,
const LaneId from,
const LaneId to);
void AddRoadSection(
const uint32_t road_id,
const uint32_t section_index,
const RoadId road_id,
const SectionId section_index,
const double s,
const double a,
const double b,
@ -187,13 +189,13 @@ namespace road {
const double d);
void SetRoadLaneLink(
const uint32_t road_id,
const int32_t section_index,
const int32_t lane_id,
const RoadId road_id,
const SectionId section_index,
const LaneId lane_id,
const Lane::LaneType lane_type,
const bool lane_level,
const int32_t predecessor,
const int32_t successor);
const LaneId predecessor,
const LaneId successor);
// called from lane parser
void CreateLaneAccess(
@ -289,27 +291,27 @@ namespace road {
const std::string unit);
void AddValidityToSignal(
const uint32_t road_id,
const uint32_t signal_id,
const int32_t from_lane,
const int32_t to_lane);
const RoadId road_id,
const SignId signal_id,
const LaneId from_lane,
const LaneId to_lane);
void AddValidityToSignalReference(
const uint32_t road_id,
const uint32_t signal_reference_id,
const int32_t from_lane,
const int32_t to_lane);
const RoadId road_id,
const SignId signal_reference_id,
const LaneId from_lane,
const LaneId to_lane);
void AddSignalReference(
const uint32_t road_id,
const uint32_t signal_reference_id,
const RoadId road_id,
const SignId signal_reference_id,
const double s_position,
const double t_position,
const std::string signal_reference_orientation);
void AddDependencyToSignal(
const uint32_t road_id,
const uint32_t signal_id,
const RoadId road_id,
const SignId signal_id,
const uint32_t dependency_id,
const std::string dependency_type);
@ -337,10 +339,13 @@ namespace road {
/// Return a list of pointers to all lanes from a lane (using road and
/// junction info).
std::vector<Lane *> GetLaneNext(RoadId road_id, int section_id, LaneId lane_id);
std::vector<Lane *> GetLaneNext(
RoadId road_id,
SectionId section_id,
LaneId lane_id);
std::vector<std::pair<RoadId, LaneId>> GetJunctionLanes(
RoadId junction_id,
JuncId junction_id,
RoadId road_id,
LaneId lane_id);

View File

@ -63,7 +63,7 @@ namespace road {
return GetRoad(road_id).GetLaneById(section_id, lane_id).template GetInfo<T>(s);
}
auto GetRoadCount() const {
size_t GetRoadCount() const {
return _roads.size();
}

View File

@ -180,7 +180,7 @@ namespace road {
}
element::DirectedPoint Road::GetDirectedPointIn(const double s) const {
const auto clamped_s = geom::Math::clamp<double>(s, 0.0, _length);
const auto clamped_s = geom::Math::Clamp(s, 0.0, _length);
const auto geometry = _info.GetInfo<element::RoadInfoGeometry>(clamped_s);
const auto lane_offset = _info.GetInfo<element::RoadInfoLaneOffset>(clamped_s);
@ -193,7 +193,7 @@ namespace road {
// Apply road's elevation record
const auto elevation_info = GetElevationOn(s);
p.location.z = elevation_info.Evaluate(s);
p.location.z = static_cast<float>(elevation_info.Evaluate(s));
p.pitch = elevation_info.Tangent(s);
return p;

View File

@ -33,11 +33,11 @@ namespace element {
DirectedPoint(const geom::Location &l, double t)
: location(l),
tangent(t) {}
DirectedPoint(double x, double y, double z, double t)
DirectedPoint(float x, float y, float z, double t)
: location(x, y, z),
tangent(t) {}
geom::Location location = {0, 0, 0};
geom::Location location = {0.0f, 0.0f, 0.0f};
double tangent = 0.0; // [radians]
double pitch = 0.0; // [radians]
@ -78,7 +78,7 @@ namespace element {
virtual DirectedPoint PosFromDist(double dist) const = 0;
virtual std::pair<double, double> DistanceTo(const geom::Location &p) const = 0;
virtual std::pair<float, float> DistanceTo(const geom::Location &p) const = 0;
protected:
@ -117,7 +117,7 @@ namespace element {
: Geometry(GeometryType::LINE, start_offset, length, heading, start_pos) {}
DirectedPoint PosFromDist(double dist) const override {
dist = geom::Math::clamp<double>(dist, 0.0, _length);
dist = geom::Math::Clamp(dist, 0.0, _length);
DEBUG_ASSERT(_length > 0.0);
DirectedPoint p(_start_position, _heading);
p.location.x += dist * std::cos(p.tangent);
@ -131,8 +131,8 @@ namespace element {
/// - @b second: Euclidean distance from the nearest point in this line to
/// p.
/// @param p point to calculate the distance
std::pair<double, double> DistanceTo(const geom::Location &p) const override {
return geom::Math::DistSegmentPoint(
std::pair<float, float> DistanceTo(const geom::Location &p) const override {
return geom::Math::DistanceSegmentToPoint(
p,
_start_position,
PosFromDist(_length).location);
@ -153,16 +153,17 @@ namespace element {
_curvature(curv) {}
DirectedPoint PosFromDist(double dist) const override {
dist = geom::Math::clamp<double>(dist, 0.0, _length);
dist = geom::Math::Clamp(dist, 0.0, _length);
DEBUG_ASSERT(_length > 0.0);
DEBUG_ASSERT(std::fabs(_curvature) > 1e-15);
const double radius = 1.0 / _curvature;
constexpr double pi_half = geom::Math::Pi<double>() / 2.0;
DirectedPoint p(_start_position, _heading);
p.location.x += radius * std::cos(p.tangent + geom::Math::pi_half());
p.location.y += radius * std::sin(p.tangent + geom::Math::pi_half());
p.location.x += radius * std::cos(p.tangent + pi_half);
p.location.y += radius * std::sin(p.tangent + pi_half);
p.tangent += dist * _curvature;
p.location.x -= radius * std::cos(p.tangent + geom::Math::pi_half());
p.location.y -= radius * std::sin(p.tangent + geom::Math::pi_half());
p.location.x -= radius * std::cos(p.tangent + pi_half);
p.location.y -= radius * std::sin(p.tangent + pi_half);
return p;
}
@ -171,13 +172,13 @@ namespace element {
/// begining of the shape.
/// - @b second: Euclidean distance from the nearest point in this arc to p.
/// @param p point to calculate the distance
std::pair<double, double> DistanceTo(const geom::Location &p) const override {
return geom::Math::DistArcPoint(
std::pair<float, float> DistanceTo(const geom::Location &p) const override {
return geom::Math::DistanceArcToPoint(
p,
_start_position,
_length,
_heading,
_curvature);
static_cast<float>(_length),
static_cast<float>(_heading),
static_cast<float>(_curvature));
}
double GetCurvature() const {
@ -213,11 +214,11 @@ namespace element {
DirectedPoint PosFromDist(double dist) const override {
// not working yet with negative values
dist = geom::Math::clamp<double>(dist, 0.0, _length);
dist = geom::Math::Clamp(dist, 0.0, _length);
DEBUG_ASSERT(_length > 0.0);
DEBUG_ASSERT(std::fabs(_curve_end) > 1e-15);
const double radius = 1.0 / _curve_end;
const double extra_norm = 1.0 / std::sqrt(geom::Math::pi_half());
const double extra_norm = 1.0 / std::sqrt(geom::Math::Pi<double>() / 2.0);
const double norm = 1.0 / std::sqrt(2.0 * radius * _length);
const double length = dist * norm;
double S, C;
@ -235,7 +236,7 @@ namespace element {
}
/// @todo
std::pair<double, double> DistanceTo(const geom::Location &) const override {
std::pair<float, float> DistanceTo(const geom::Location &) const override {
throw_exception(std::runtime_error("not implemented"));
}

View File

@ -19,9 +19,9 @@ namespace general {
public:
Validity(
int32_t parent_id,
int32_t from_lane,
int32_t to_lane)
uint32_t parent_id,
road::LaneId from_lane,
road::LaneId to_lane)
: _parent_id(parent_id),
_from_lane(from_lane),
_to_lane(to_lane) {}
@ -32,9 +32,9 @@ namespace general {
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wunused-private-field"
#endif
int32_t _parent_id;
int32_t _from_lane;
int32_t _to_lane;
uint32_t _parent_id;
road::LaneId _from_lane;
road::LaneId _to_lane;
#if defined(__clang__)
# pragma clang diagnostic pop
#endif

View File

@ -22,8 +22,8 @@ namespace signal {
public:
Signal(
int32_t road_id,
int32_t signal_id,
road::RoadId road_id,
road::SignId signal_id,
double s,
double t,
std::string name,
@ -75,8 +75,8 @@ namespace signal {
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wunused-private-field"
#endif
int32_t _road_id;
int32_t _signal_id;
road::RoadId _road_id;
road::SignId _signal_id;
double _s;
double _t;
std::string _name;

View File

@ -7,11 +7,12 @@
#pragma once
#include "carla/NonCopyable.h"
#include <string>
#include <vector>
#include "carla/road/RoadTypes.h"
#include "carla/road/general/Validity.h"
#include <string>
#include <vector>
namespace carla {
namespace road {
namespace signal {
@ -20,8 +21,8 @@ namespace signal {
public:
SignalDependency(
int32_t road_id,
uint32_t signal_id,
road::RoadId road_id,
road::SignId signal_id,
uint32_t dependency_id,
std::string type)
: _road_id(road_id),
@ -35,9 +36,9 @@ namespace signal {
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wunused-private-field"
#endif
int32_t _road_id;
int32_t _signal_id;
int32_t _dependency_id;
road::RoadId _road_id;
road::SignId _signal_id;
uint32_t _dependency_id;
std::string _type;
#if defined(__clang__)
# pragma clang diagnostic pop

View File

@ -20,8 +20,8 @@ namespace signal {
public:
SignalReference(
int32_t road_id,
uint32_t id,
road::RoadId road_id,
road::SignId id,
double s,
double t,
std::string orientation)
@ -41,8 +41,8 @@ namespace signal {
# pragma clang diagnostic push
# pragma clang diagnostic ignored "-Wunused-private-field"
#endif
int32_t _road_id;
int32_t _signal_id;
road::RoadId _road_id;
road::SignId _signal_id;
double _s;
double _t;
std::string _orientation;

View File

@ -80,7 +80,8 @@ namespace sensor {
/// Size in bytes of the data generated by the sensor.
size_t size() const {
return std::distance(begin(), end());
DEBUG_ASSERT(std::distance(begin(), end()) >= 0);
return static_cast<size_t>(std::distance(begin(), end()));
}
private:

View File

@ -87,7 +87,8 @@ namespace data {
}
size_type size() const {
return std::distance(begin(), end());
DEBUG_ASSERT(std::distance(begin(), end()) >= 0);
return static_cast<size_type>(std::distance(begin(), end()));
}
value_type *data() {

View File

@ -27,7 +27,7 @@ static auto MakeTestImage(size_t width, size_t height) {
width,
height,
reinterpret_cast<PixelT*>(data.get()),
sizeof(PixelT) * width);
static_cast<long>(sizeof(PixelT) * width));
return TestImage<decltype(view), PixelT>{std::move(data), view};
}
@ -77,9 +77,9 @@ TEST(image, depth) {
for (auto b = 0u; b < 256u; ++b) {
decltype(img_bgra8)::pixel_type &p_bgra8 = *it_bgra8;
decltype(img_gray8)::pixel_type &p_gray8 = *it_gray8;
get_color(p_bgra8, red_t()) = r;
get_color(p_bgra8, green_t()) = g;
get_color(p_bgra8, blue_t()) = b;
get_color(p_bgra8, red_t()) = static_cast<uint8_t>(r);
get_color(p_bgra8, green_t()) = static_cast<uint8_t>(g);
get_color(p_bgra8, blue_t()) = static_cast<uint8_t>(b);
const float depth = r + (g * 256) + (b * 256 * 256);
const float normalized = depth / static_cast<float>(256 * 256 * 256 - 1);
p_gray8[0] = static_cast<uint8_t>(255.0 * normalized);
@ -146,11 +146,11 @@ TEST(image, semantic_segmentation) {
for (auto tag = 0u; tag < width; ++tag) {
decltype(img_bgra8)::pixel_type &p_bgra8 = *it_bgra8;
get_color(p_bgra8, red_t()) = tag;
get_color(p_bgra8, red_t()) = static_cast<uint8_t>(tag);
get_color(p_bgra8, green_t()) = 0u;
get_color(p_bgra8, blue_t()) = 0u;
decltype(img_ss)::pixel_type &p_ss = *it_ss;
auto color = CityScapesPalette::GetColor(tag);
auto color = CityScapesPalette::GetColor(static_cast<uint8_t>(tag));
get_color(p_ss, red_t()) = color[0u];
get_color(p_ss, green_t()) = color[1u];
get_color(p_ss, blue_t()) = color[2u];

View File

@ -32,17 +32,17 @@ using namespace util;
const std::string BASE_PATH = LIBCARLA_TEST_CONTENT_FOLDER "/OpenDrive/";
// Road Elevation
void test_road_elevation(const pugi::xml_document &xml, boost::optional<Map>& map ) {
static void test_road_elevation(const pugi::xml_document &xml, boost::optional<Map>& map) {
pugi::xml_node open_drive_node = xml.child("OpenDRIVE");
for (pugi::xml_node road_node : open_drive_node.children("road")) {
RoadId road_id = road_node.attribute("id").as_int();
RoadId road_id = road_node.attribute("id").as_uint();
auto elevation_profile_nodes = road_node.children("elevationProfile");
for (pugi::xml_node elevation_profile_node : elevation_profile_nodes) {
size_t total_elevations = 0;
auto total_elevations = 0;
auto elevation_nodes = elevation_profile_node.children("elevation");
size_t total_elevation_parser = std::distance(elevation_nodes.begin(), elevation_nodes.end());
auto total_elevation_parser = std::distance(elevation_nodes.begin(), elevation_nodes.end());
for (pugi::xml_node elevation_node : elevation_nodes) {
float s = elevation_node.attribute("s").as_float();
@ -56,18 +56,16 @@ void test_road_elevation(const pugi::xml_document &xml, boost::optional<Map>& ma
}
// Geometry
void test_geometry(const pugi::xml_document &xml, boost::optional<Map>& map)
{
static void test_geometry(const pugi::xml_document &xml, boost::optional<Map>& map) {
pugi::xml_node open_drive_node = xml.child("OpenDRIVE");
for (pugi::xml_node road_node : open_drive_node.children("road")) {
RoadId road_id = road_node.attribute("id").as_int();
RoadId road_id = road_node.attribute("id").as_uint();
for (pugi::xml_node plan_view_nodes : road_node.children("planView")) {
auto geometries_parser = plan_view_nodes.children("geometry");
size_t total_geometries_parser = std::distance(geometries_parser.begin(), geometries_parser.end());
size_t total_geometries = 0;
auto total_geometries_parser = std::distance(geometries_parser.begin(), geometries_parser.end());
auto total_geometries = 0;
for (pugi::xml_node geometry_node : plan_view_nodes.children("geometry")){
float s = geometry_node.attribute("s").as_float();
auto geometry = map->GetMap().GetRoad(road_id).GetInfo<RoadInfoGeometry>(s);
@ -80,10 +78,12 @@ void test_geometry(const pugi::xml_document &xml, boost::optional<Map>& map)
}
// Road test
auto get_total_road_marks (pugi::xml_object_range<pugi::xml_named_node_iterator> &lane_nodes, LaneSection& lane_section, float) {
static auto get_total_road_marks(
pugi::xml_object_range<pugi::xml_named_node_iterator> &lane_nodes,
LaneSection& lane_section) {
constexpr auto error = 1e-5;
size_t total_road_mark = 0;
size_t total_road_mark_parser = 0;
auto total_road_mark = 0;
auto total_road_mark_parser = 0;
for (pugi::xml_node lane_node : lane_nodes) {
// Check Road Mark
auto road_mark_nodes = lane_node.children("roadMark");
@ -113,25 +113,24 @@ auto get_total_road_marks (pugi::xml_object_range<pugi::xml_named_node_iterator>
return std::make_pair(total_road_mark, total_road_mark_parser);
}
void test_roads(const pugi::xml_document &xml, boost::optional<Map>& map)
{
static void test_roads(const pugi::xml_document &xml, boost::optional<Map>& map) {
pugi::xml_node open_drive_node = xml.child("OpenDRIVE");
// Check total Roads
auto roads_parser = open_drive_node.children("road");
size_t total_roads_parser = std::distance(roads_parser.begin(), roads_parser.end());
size_t total_roads = map->GetMap().GetRoads().size();
auto total_roads_parser = std::distance(roads_parser.begin(), roads_parser.end());
auto total_roads = map->GetMap().GetRoads().size();
ASSERT_EQ(total_roads, total_roads_parser);
for (pugi::xml_node road_node : roads_parser) {
RoadId road_id = road_node.attribute("id").as_int();
RoadId road_id = road_node.attribute("id").as_uint();
for (pugi::xml_node lanes_node : road_node.children("lanes")) {
// Check total Lane Sections
auto lane_sections_parser = lanes_node.children("laneSection");
size_t total_lane_sections_parser = std::distance(lane_sections_parser.begin(), lane_sections_parser.end());
size_t total_lane_sections = map->GetMap().GetRoad(road_id).GetLaneSections().size();
auto total_lane_sections_parser = std::distance(lane_sections_parser.begin(), lane_sections_parser.end());
auto total_lane_sections = map->GetMap().GetRoad(road_id).GetLaneSections().size();
ASSERT_EQ(total_lane_sections, total_lane_sections_parser);
for (pugi::xml_node lane_section_node : lane_sections_parser) {
@ -146,19 +145,19 @@ void test_roads(const pugi::xml_document &xml, boost::optional<Map>& map)
auto left_nodes = lane_section_node.child("left").children("lane");
auto center_nodes = lane_section_node.child("center").children("lane");
auto right_nodes = lane_section_node.child("right").children("lane");
size_t total_lanes_parser = std::distance(left_nodes.begin(), left_nodes.end());
auto total_lanes_parser = std::distance(left_nodes.begin(), left_nodes.end());
total_lanes_parser += std::distance(right_nodes.begin(), right_nodes.end());
total_lanes_parser += std::distance(center_nodes.begin(), center_nodes.end());
ASSERT_EQ(total_lanes, total_lanes_parser);
size_t total_road_mark = 0;
size_t total_road_mark_parser = 0;
auto total_road_mark = 0;
auto total_road_mark_parser = 0;
for (auto it = lane_section.begin(); it != lane_section.end(); ++it) {
auto total_left = get_total_road_marks(left_nodes, *it, s);
auto total_center = get_total_road_marks(center_nodes, *it, s);
auto total_right = get_total_road_marks(right_nodes, *it, s);
auto total_left = get_total_road_marks(left_nodes, *it);
auto total_center = get_total_road_marks(center_nodes, *it);
auto total_right = get_total_road_marks(right_nodes, *it);
total_road_mark = total_left.first + total_center.first + total_right.first;
total_road_mark_parser = total_left.first + total_center.first + total_right.first;
}
@ -169,20 +168,18 @@ void test_roads(const pugi::xml_document &xml, boost::optional<Map>& map)
}
// Junctions
void test_junctions(const pugi::xml_document &xml, boost::optional<Map>& map)
{
static void test_junctions(const pugi::xml_document &xml, boost::optional<Map>& map) {
pugi::xml_node open_drive_node = xml.child("OpenDRIVE");
// Check total number of junctions
auto& junctions = map->GetMap().GetJunctions();
size_t total_junctions_parser = std::distance(open_drive_node.children("junction").begin(), open_drive_node.children("junction").end());
auto total_junctions_parser = std::distance(open_drive_node.children("junction").begin(), open_drive_node.children("junction").end());
ASSERT_EQ(junctions.size(), total_junctions_parser);
for (pugi::xml_node junction_node : open_drive_node.children("junction")) {
// Check total number of connections
size_t total_connections_parser = std::distance(junction_node.children("connection").begin(), junction_node.children("connection").end());
auto total_connections_parser = std::distance(junction_node.children("connection").begin(), junction_node.children("connection").end());
JuncId junction_id = junction_node.attribute("id").as_int();
auto& junction = junctions.find(junction_id)->second;
@ -192,7 +189,7 @@ void test_junctions(const pugi::xml_document &xml, boost::optional<Map>& map)
ASSERT_EQ(connections.size(), total_connections_parser);
for (pugi::xml_node connection_node : junction_node.children("connection")) {
size_t total_lane_links_parser = std::distance(connection_node.children("laneLink").begin(), connection_node.children("laneLink").end());
auto total_lane_links_parser = std::distance(connection_node.children("laneLink").begin(), connection_node.children("laneLink").end());
ConId connection_id = connection_node.attribute("id").as_uint();
auto& connection = connections.find(connection_id)->second;
@ -205,7 +202,7 @@ void test_junctions(const pugi::xml_document &xml, boost::optional<Map>& map)
}
}
void test_road_links(boost::optional<Map>& map) {
static void test_road_links(boost::optional<Map>& map) {
// process all roads, sections and lanes
for (auto &road : map->GetMap().GetRoads()) {
@ -224,108 +221,6 @@ void test_road_links(boost::optional<Map>& map) {
}
}
void print_roads(boost::optional<Map>& map, std::string filename) {
std::ofstream file;
std::string name;
// write TXT with road links
name = filename + ".txt";
file.open(name, std::ios::out | std::ios::trunc);
for (auto &road : map->GetMap().GetRoads()) {
file << "Road: " << road.second.GetId() << std::endl;
file << " Nexts: ";
for (auto next : road.second.GetNexts()) {
if (next != nullptr) {
file << next->GetId() << " ";
} else {
file << " (error, null road)";
}
}
file << std::endl;
file << " Prevs: ";
for (auto prev : road.second.GetPrevs()) {
if (prev != nullptr) {
file << prev->GetId() << " ";
} else {
file << " (error, null road)";
}
}
file << std::endl;
for (auto &section : road.second.GetLaneSections()) {
file << " Section: " << section.GetId() << " " << section.GetDistance() << std::endl;
for (auto &lane : section.GetLanes()) {
file << " Lane: " << lane.second.GetId() << " (" << static_cast<uint32_t>(lane.second.GetType()) << ")" << std::endl;
file << " Nexts: ";
for (auto link : lane.second.GetNextLanes()) {
if (link != nullptr) {
file << " (" << link->GetRoad()->GetId() << "," << link->GetId() << ")";
} else {
file << " (error, null lane)";
}
}
file << std::endl;
file << " Prevs: ";
for (auto link : lane.second.GetPreviousLanes()) {
if (link != nullptr) {
file << " (" << link->GetRoad()->GetId() << "," << link->GetId() << ")";
} else {
file << " (error, null lane)";
}
}
file << std::endl;
}
}
}
file.close();
// write TGF with nodes links to be imported in Yed
// 1 a ; node 1 with label 'a'
// 2 b ; node 2 with label 'b'
// #
// 2 1 c ; edge from node 2 to 1 with label 'c'
name = filename + ".tgf";
file.open(name, std::ios::out | std::ios::trunc);
for (auto &road : map->GetMap().GetRoads()) {
std::stringstream road_name;
if (road.second.IsJunction()) {
road_name << "." << road.second.GetId() << ".";
} else {
road_name << road.second.GetId();
}
file << road.second.GetId() << " " << road_name.str() << std::endl;
}
file << "#" << std::endl;
// by roads
for (auto &road : map->GetMap().GetRoads()) {
for (auto next : road.second.GetNexts()) {
if (next != nullptr) {
file << road.second.GetId() << " " << next->GetId() << std::endl;
} else {
file << " (error, null road)";
}
}
}
/* by lanes
for (auto &road : map->GetMap().GetRoads()) {
for (auto &section : road.second.GetLaneSections()) {
for (auto &lane : section.GetLanes()) {
for (auto link : lane.second.GetNextLanes()) {
if (link->GetRoad()->GetId() != road.second.GetId()) {
file << road.second.GetId() << " " << link->GetRoad()->GetId() << " (" << lane.second.GetId() << "," << link->GetId() << ")" << std::endl;
}
}
// for (auto link : lane.second.GetPreviousLanes()) {
// if (link->GetRoad()->GetId() != road.second.GetId()) {
// file << road.second.GetId() << " " << link->GetRoad()->GetId() << " (" << lane.second.GetId() << "," << link->GetId() << ")" << std::endl;
// }
// }
}
}
}
*/
file.close();
}
TEST(road, parse_files) {
for (const auto &file : util::OpenDrive::GetAvailableFiles()) {
// std::cerr << file << std::endl;

View File

@ -29,7 +29,7 @@ TEST(rpc, compilation_tests) {
TEST(rpc, server_bind_sync_run_on_game_thread) {
const auto main_thread_id = std::this_thread::get_id();
const auto port = (TESTING_PORT != 0u ? TESTING_PORT : 2017u);
const uint16_t port = (TESTING_PORT != 0u ? TESTING_PORT : 2017u);
Server server(port);

View File

@ -91,7 +91,7 @@ TEST(buffer, copy_with_offset) {
const char str0[] = "Hello";
const char str1[] = "buffer!";
Buffer buffer;
auto offset = sizeof(str0);
auto offset = static_cast<Buffer::size_type>(sizeof(str0));
buffer.copy_from(
offset,
reinterpret_cast<const unsigned char *>(&str1),

View File

@ -135,7 +135,7 @@ TEST(geom, nearest_point_segment) {
double min_dist = std::numeric_limits<double>::max();
int id = -1;
for (int j = 0; j < 40; j += 4) {
const double dist = Math::DistSegmentPoint(
const double dist = Math::DistanceSegmentToPoint(
point[i],
{segment[j + 0], segment[j + 1], 0},
{segment[j + 2], segment[j + 3], 0}).second;
@ -169,52 +169,13 @@ TEST(geom, forward_vector) {
compare({180.0f, -90.0f, 0.0f}, {0.0f, 1.0f, 0.0f});
}
TEST(geom, point_in_rectangle) {
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(0, 0, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(1, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(-1, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(1, -1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(-1, -1, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(-1.01, -1.01, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), 0, Vector3D(1.01, 1.01, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(0, 0, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(1, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(2, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(2, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(2, 2, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(1.5, 1.5, 0), Vector3D(1, 1, 0), 0, Vector3D(1, 1, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), Math::pi_half() * 0.5, Vector3D(1, 1, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 0, 0), Vector3D(1, 1, 0), Math::pi_half() * 0.5, Vector3D(1, 0, 0)));
ASSERT_TRUE(Math::PointInRectangle(
Vector3D(0, 2, 0), Vector3D(0.5, 2, 0), Math::pi_half(), Vector3D(2, 2, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(0, 2, 0), Vector3D(0.5, 2, 0), Math::pi_half(), Vector3D(2.1, 2, 0)));
ASSERT_FALSE(Math::PointInRectangle(
Vector3D(0, 2, 0), Vector3D(0.5, 2, 0), Math::pi_half(), Vector3D(2, 2.6, 0)));
}
TEST(geom, nearest_point_arc) {
ASSERT_NEAR(Math::DistArcPoint(Vector3D(1,0,0),
Vector3D(0,0,0), 1.57, 0, 1).second, 0.414214, 0.01);
ASSERT_NEAR(Math::DistArcPoint(Vector3D(2,1,0),
Vector3D(0,0,0), 1.57, 0, 1).second, 1.0, 0.01);
ASSERT_NEAR(Math::DistArcPoint(Vector3D(0,1,0),
Vector3D(0,0,0), 1.57, 0, 1).second, 1.0, 0.01);
ASSERT_NEAR(Math::DistArcPoint(Vector3D(1,2,0),
Vector3D(0,0,0), 1.57, 0, 1).second, 1.0, 0.01);
ASSERT_NEAR(Math::DistanceArcToPoint(Vector3D(1,0,0),
Vector3D(0,0,0), 1.57f, 0, 1).second, 0.414214f, 0.01f);
ASSERT_NEAR(Math::DistanceArcToPoint(Vector3D(2,1,0),
Vector3D(0,0,0), 1.57f, 0, 1).second, 1.0f, 0.01f);
ASSERT_NEAR(Math::DistanceArcToPoint(Vector3D(0,1,0),
Vector3D(0,0,0), 1.57f, 0, 1).second, 1.0f, 0.01f);
ASSERT_NEAR(Math::DistanceArcToPoint(Vector3D(1,2,0),
Vector3D(0,0,0), 1.57f, 0, 1).second, 1.0f, 0.01f);
}

View File

@ -20,6 +20,6 @@ TEST(vector3D, make_unit_vec) {
ASSERT_NE(Vector3D(0,1,512).MakeUnitVector(), Vector3D(0,0,1));
#ifndef NDEBUG
ASSERT_DEATH_IF_SUPPORTED(
Vector3D().MakeUnitVector(), "len > std::numeric_limits<double>::epsilon()");
Vector3D().MakeUnitVector(), "length > 2.0f \\* std::numeric_limits<float>::epsilon()");
#endif // NDEBUG
}
}

View File

@ -44,6 +44,7 @@ def get_libcarla_extensions():
'-Wdeprecated', '-Wno-shadow', '-Wuninitialized', '-Wunreachable-code',
'-Wpessimizing-move', '-Wold-style-cast', '-Wnull-dereference',
'-Wduplicate-enum', '-Wnon-virtual-dtor', '-Wheader-hygiene',
'-Wconversion', '-Wfloat-overflow-conversion',
'-DBOOST_ERROR_CODE_HEADER_ONLY', '-DLIBCARLA_WITH_PYTHON_SUPPORT'
]
if 'TRAVIS' in os.environ and os.environ['TRAVIS'] == 'true':

View File

@ -66,8 +66,8 @@ void export_client() {
.def("stop_recorder", &cc::Client::StopRecorder)
.def("show_recorder_file_info", CALL_WITHOUT_GIL_2(cc::Client, ShowRecorderFileInfo, std::string, bool), (arg("name"), arg("show_all")))
.def("show_recorder_collisions", CALL_WITHOUT_GIL_3(cc::Client, ShowRecorderCollisions, std::string, char, char), (arg("name"), arg("type1"), arg("type2")))
.def("show_recorder_actors_blocked", CALL_WITHOUT_GIL_3(cc::Client, ShowRecorderActorsBlocked, std::string, float, float), (arg("name"), arg("min_time"), arg("min_distance")))
.def("replay_file", CALL_WITHOUT_GIL_4(cc::Client, ReplayFile, std::string, float, float, int), (arg("name"), arg("time_start"), arg("duration"), arg("follow_id")))
.def("show_recorder_actors_blocked", CALL_WITHOUT_GIL_3(cc::Client, ShowRecorderActorsBlocked, std::string, double, double), (arg("name"), arg("min_time"), arg("min_distance")))
.def("replay_file", CALL_WITHOUT_GIL_4(cc::Client, ReplayFile, std::string, double, double, uint32_t), (arg("name"), arg("time_start"), arg("duration"), arg("follow_id")))
.def("set_replayer_time_factor", &cc::Client::SetReplayerTimeFactor, (arg("time_factor")))
.def("apply_batch", &ApplyBatchCommands, (arg("commands"), arg("do_tick")=false))
.def("apply_batch_sync", &ApplyBatchCommandsSync, (arg("commands"), arg("do_tick")=false))

View File

@ -68,7 +68,7 @@ static auto GetVectorOfVector2DFromList(const boost::python::list &list) {
std::vector<carla::geom::Vector2D> v;
auto length = boost::python::len(list);
v.reserve(length);
v.reserve(static_cast<size_t>(length));
for (auto i = 0u; i < length; ++i) {
boost::python::extract<carla::geom::Vector2D> ext(list[i]);
if (ext.check()) {

View File

@ -89,10 +89,10 @@ enum class EColorConverter {
template <typename T>
static auto GetRawDataAsBuffer(T &self) {
auto *data = reinterpret_cast<unsigned char *>(self.data());
auto size = sizeof(typename T::value_type) * self.size();
#if PY_MAJOR_VERSION >= 3 // NOTE(Andrei): python 3
auto size = static_cast<Py_ssize_t>(sizeof(typename T::value_type) * self.size());
#if PY_MAJOR_VERSION >= 3
auto *ptr = PyMemoryView_FromMemory(reinterpret_cast<char *>(data), size, PyBUF_READ);
#else // NOTE(Andrei): python 2
#else
auto *ptr = PyBuffer_FromMemory(data, size);
#endif
return boost::python::object(boost::python::handle<>(ptr));

View File

@ -314,6 +314,7 @@ set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Werror -Wall -Wextra -Wpedantic" CACHE
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wdeprecated -Wshadow -Wuninitialized -Wunreachable-code" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wpessimizing-move -Wold-style-cast -Wnull-dereference" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wduplicate-enum -Wnon-virtual-dtor -Wheader-hygiene" CACHE STRING "" FORCE)
set(CMAKE_CXX_FLAGS "\${CMAKE_CXX_FLAGS} -Wconversion -Wfloat-overflow-conversion" CACHE STRING "" FORCE)
# @todo These flags need to be compatible with setup.py compilation.
set(CMAKE_CXX_FLAGS_RELEASE_CLIENT "\${CMAKE_CXX_FLAGS_RELEASE} -DNDEBUG -g -fwrapv -O2 -Wall -Wstrict-prototypes -fno-strict-aliasing -Wdate-time -D_FORTIFY_SOURCE=2 -g -fstack-protector-strong -Wformat -Werror=format-security -fPIC -std=c++14 -Wno-missing-braces -DBOOST_ERROR_CODE_HEADER_ONLY -DLIBCARLA_WITH_PYTHON_SUPPORT" CACHE STRING "" FORCE)