Code format according to google style

and tried to spot the remaining CamelStyle variable names and changed to
snake_style

Added code formatting script and clang-format slightly changed from
google format:
AccessModifierOffset: -1 -> -2
AllowShortFunctionsOnASingleLine: All -> Empty
ConstructorInitializerIndentWidth: 4 -> 2
This commit is contained in:
Bernd Gassmann 2020-03-25 18:10:25 +01:00
parent 45d0554483
commit 67b17ee42a
11 changed files with 1597 additions and 764 deletions

File diff suppressed because it is too large Load Diff

View File

@ -5,6 +5,7 @@
#pragma once
#include <spdlog/spdlog.h>
#include <ad/map/landmark/LandmarkIdSet.hpp>
#include <ad/map/match/Object.hpp>
#include <ad/map/route/FullRoute.hpp>
@ -13,10 +14,9 @@
#include <ad/rss/situation/SituationSnapshot.hpp>
#include <ad/rss/state/ProperResponse.hpp>
#include <ad/rss/state/RssStateSnapshot.hpp>
#include <iostream>
#include <memory>
#include <mutex>
#include <iostream>
#include <spdlog/spdlog.h>
#include "carla/client/ActorList.h"
#include "carla/client/Vehicle.h"
#include "carla/road/Map.h"
@ -27,28 +27,35 @@ namespace rss {
/// @brief struct defining the different supported handling of road boundaries
enum class RoadBoundariesMode {
Off, /// No road boundaries considered by RSS check
On /// The road boundaries of the current route are considered by RSS check
On /// The road boundaries of the current route are considered by RSS check
};
/// @brief struct defining the different supported handling of debug visualization
/// @brief struct defining the different supported handling of debug
/// visualization
enum class VisualizationMode {
Off, /// Nothing is visualized
RouteOnly, /// Only the route is visualized
DebugRouteOrientationObjectRoute, /// Only the route section around the object is visualized
DebugRouteOrientationBorders, /// Only the route section transformed into borders around the object is visualized
DebugRouteOrientationBoth, /// The route section around the object and the transformed borders are visualized
VehicleStateOnly, /// Only the states of the vehicles is visualized
VehicleStateAndRoute, /// The states of the vehicles and the route is visualized
All /// All (except debug) is visualized
Off, /// Nothing is visualized
RouteOnly, /// Only the route is visualized
DebugRouteOrientationObjectRoute, /// Only the route section around the
/// object
/// is visualized
DebugRouteOrientationBorders, /// Only the route section transformed into
/// borders around the object is visualized
DebugRouteOrientationBoth, /// The route section around the object and the
/// transformed borders are visualized
VehicleStateOnly, /// Only the states of the vehicles is visualized
VehicleStateAndRoute, /// The states of the vehicles and the route is
/// visualized
All /// All (except debug) is visualized
};
/// @brief struct defining the ego vehicles current dynamics in respect to the current route
/// @brief struct defining the ego vehicles current dynamics in respect to the
/// current route
///
/// Especially the velocity of the vehicle is split into lateral and longitudinal components
/// Especially the velocity of the vehicle is split into lateral and
/// longitudinal components
/// according to the current route
///
struct EgoDynamicsOnRoute {
/// @brief constructor
EgoDynamicsOnRoute();
@ -68,7 +75,8 @@ struct EgoDynamicsOnRoute {
::ad::map::point::ENUHeading ego_heading;
/// @brief check if the ego center is within route
bool ego_center_within_route;
/// @brief flag indicating if the current state is already crossing one of the borders
/// @brief flag indicating if the current state is already crossing one of the
/// borders
/// this is only evaluated if the border checks are active!
/// It is a hint to oversteer a bit on countersteering
bool crossing_border;
@ -94,9 +102,9 @@ struct EgoDynamicsOnRoute {
::ad::physics::Acceleration avg_route_accel_lon;
};
/// @brief class implementing the actual RSS checks based on CARLA world description
/// @brief class implementing the actual RSS checks based on CARLA world
/// description
class RssCheck {
public:
/// @brief constructor
RssCheck();
@ -109,48 +117,63 @@ public:
/// This function has to be called cyclic with increasing timestamps to ensure
/// proper RSS evaluation.
///
bool CheckObjects(carla::client::Timestamp const &timestamp,
carla::SharedPtr<carla::client::ActorList> const &actors,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
::ad::rss::state::ProperResponse &output_response,
::ad::rss::world::AccelerationRestriction &output_acceleration_restriction,
::ad::rss::state::RssStateSnapshot &output_rss_state_snapshot,
EgoDynamicsOnRoute &output_rss_ego_dynamics_on_route);
bool CheckObjects(
carla::client::Timestamp const &timestamp,
carla::SharedPtr<carla::client::ActorList> const &actors,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
::ad::rss::state::ProperResponse &output_response,
::ad::rss::world::AccelerationRestriction
&output_acceleration_restriction,
::ad::rss::state::RssStateSnapshot &output_rss_state_snapshot,
EgoDynamicsOnRoute &output_rss_ego_dynamics_on_route);
/// @brief function to visualize the RSS check results
///
void VisualizeResults(carla::client::World &world,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor) const;
void VisualizeResults(
carla::client::World &world,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor) const;
/// @returns the used vehicle dynamics for ego vehcile
const ::ad::rss::world::RssDynamics& GetEgoVehicleDynamics() const;
const ::ad::rss::world::RssDynamics &GetEgoVehicleDynamics() const;
/// @brief sets the vehicle dynamics to be used for the ego vehcile
void SetEgoVehicleDynamics(const ::ad::rss::world::RssDynamics &ego_vehicle_dynamics);
void SetEgoVehicleDynamics(
const ::ad::rss::world::RssDynamics &ego_vehicle_dynamics);
/// @returns the used vehicle dynamics for other vehciles
const ::ad::rss::world::RssDynamics& GetOtherVehicleDynamics() const;
const ::ad::rss::world::RssDynamics &GetOtherVehicleDynamics() const;
/// @brief sets the vehicle dynamics to be used for other vehciles
void SetOtherVehicleDynamics(const ::ad::rss::world::RssDynamics &other_vehicle_dynamics);
void SetOtherVehicleDynamics(
const ::ad::rss::world::RssDynamics &other_vehicle_dynamics);
/// @returns the current mode for respecting the road boundaries (@see also RssSensor::GetRoadBoundariesMode())
const ::carla::rss::RoadBoundariesMode& GetRoadBoundariesMode() const;
/// @brief sets the current mode for respecting the road boundaries (@see also RssSensor::SetRoadBoundariesMode())
void SetRoadBoundariesMode(const ::carla::rss::RoadBoundariesMode &road_boundaries_mode);
/// @returns the current mode for respecting the road boundaries (@see also
/// RssSensor::GetRoadBoundariesMode())
const ::carla::rss::RoadBoundariesMode &GetRoadBoundariesMode() const;
/// @brief sets the current mode for respecting the road boundaries (@see also
/// RssSensor::SetRoadBoundariesMode())
void SetRoadBoundariesMode(
const ::carla::rss::RoadBoundariesMode &road_boundaries_mode);
/// @returns the current routing targets (@see also RssSensor::GetRoutingTargets())
/// @returns the current routing targets (@see also
/// RssSensor::GetRoutingTargets())
const std::vector<::carla::geom::Transform> GetRoutingTargets() const;
/// @brief appends a routing target to the current routing target list (@see also RssSensor::AppendRoutingTargets())
/// @brief appends a routing target to the current routing target list (@see
/// also RssSensor::AppendRoutingTargets())
void AppendRoutingTarget(const ::carla::geom::Transform &routing_target);
/// @brief resets the current routing targets (@see also RssSensor::ResetRoutingTargets())
/// @brief resets the current routing targets (@see also
/// RssSensor::ResetRoutingTargets())
void ResetRoutingTargets();
/// @brief sets the visualization mode (@see also ::carla::rss::VisualizationMode)
void SetVisualizationMode(const ::carla::rss::VisualizationMode &visualization_mode);
/// @returns get the current visualization mode (@see also ::carla::rss::VisualizationMode)
const ::carla::rss::VisualizationMode& GetVisualizationMode() const;
/// @brief sets the visualization mode (@see also
/// ::carla::rss::VisualizationMode)
void SetVisualizationMode(
const ::carla::rss::VisualizationMode &visualization_mode);
/// @returns get the current visualization mode (@see also
/// ::carla::rss::VisualizationMode)
const ::carla::rss::VisualizationMode &GetVisualizationMode() const;
/// @brief drop the current route
///
/// Afterwards a new route is selected randomly (if multiple routes are possible).
/// Afterwards a new route is selected randomly (if multiple routes are
/// possible).
///
void DropRoute();
@ -199,20 +222,26 @@ private:
::ad::rss::world::AccelerationRestriction acceleration_restriction;
/// @brief flag indicating if the current state is overall dangerous
bool dangerous_state;
/// @brief flag indicating if the current state is dangerous because of a vehicle
/// @brief flag indicating if the current state is dangerous because of a
/// vehicle
bool dangerous_vehicle;
/// @brief flag indicating if the current state is dangerous because of an opposite vehicle
/// @brief flag indicating if the current state is dangerous because of an
/// opposite vehicle
bool dangerous_opposite_state;
};
class RssObjectChecker {
public:
RssObjectChecker(RssCheck const& rss_check, ::ad::rss::map::RssSceneCreation &scene_creation, carla::client::Vehicle const &carla_ego_vehicle, CarlaRssState const &carla_rss_state,
::ad::map::landmark::LandmarkIdSet const &green_traffic_lights);
void operator()( const carla::SharedPtr<carla::client::Actor> actor ) const;
RssObjectChecker(
RssCheck const &rss_check,
::ad::rss::map::RssSceneCreation &scene_creation,
carla::client::Vehicle const &carla_ego_vehicle,
CarlaRssState const &carla_rss_state,
::ad::map::landmark::LandmarkIdSet const &green_traffic_lights);
void operator()(const carla::SharedPtr<carla::client::Actor> actor) const;
private:
RssCheck const& _rss_check;
RssCheck const &_rss_check;
::ad::rss::map::RssSceneCreation &_scene_creation;
carla::client::Vehicle const &_carla_ego_vehicle;
CarlaRssState const &_carla_rss_state;
@ -228,26 +257,30 @@ private:
::ad::rss::world::RssDynamics GetDefaultVehicleDynamics() const;
/// @brief calculate the map matched object from the carla_vehicle
::ad::map::match::Object GetMatchObject(carla::client::Vehicle const &carla_vehicle,
::ad::physics::Distance const &match_distance) const;
::ad::map::match::Object GetMatchObject(
carla::client::Vehicle const &carla_vehicle,
::ad::physics::Distance const &match_distance) const;
/// @brief calculate the speed from the carla_vehicle
::ad::physics::Speed GetSpeed(carla::client::Vehicle const &carla_vehicle) const;
::ad::physics::Speed GetSpeed(
carla::client::Vehicle const &carla_vehicle) const;
/// @brief update the desired ego vehicle route
void UpdateRoute(CarlaRssState &carla_rss_state);
/// @brief calculate ego vehicle dynamics on the route
EgoDynamicsOnRoute CalculateEgoDynamicsOnRoute(carla::client::Timestamp const &current_timestamp,
double const &time_since_epoch_check_start_ms,
carla::client::Vehicle const &carla_vehicle,
::ad::map::match::Object match_object,
::ad::map::route::FullRoute const &route,
EgoDynamicsOnRoute const &last_dynamics) const;
EgoDynamicsOnRoute CalculateEgoDynamicsOnRoute(
carla::client::Timestamp const &current_timestamp,
double const &time_since_epoch_check_start_ms,
carla::client::Vehicle const &carla_vehicle,
::ad::map::match::Object match_object,
::ad::map::route::FullRoute const &route,
EgoDynamicsOnRoute const &last_dynamics) const;
/// @brief collect the green traffic lights on the current route
::ad::map::landmark::LandmarkIdSet GetGreenTrafficLightsOnRoute(carla::client::ActorList const &actors,
::ad::map::route::FullRoute const&route) const;
::ad::map::landmark::LandmarkIdSet GetGreenTrafficLightsOnRoute(
carla::client::ActorList const &actors,
::ad::map::route::FullRoute const &route) const;
/// @brief Create the RSS world model
void CreateWorldModel(carla::client::Timestamp const &timestamp,
@ -266,24 +299,25 @@ private:
///
void StoreVisualizationResults(CarlaRssState const &carla_rss_state);
void StoreDebugVisualization(::ad::map::route::FullRoute const &debug_route,
std::vector<::ad::map::lane::ENUBorder> const &enu_border) const;
void StoreDebugVisualization(
::ad::map::route::FullRoute const &debug_route,
std::vector<::ad::map::lane::ENUBorder> const &enu_border) const;
/// mutex to protect the visualization content
mutable std::mutex _visualization_mutex;
/// the RssStateSnapshot to be visualized
::ad::rss::state::RssStateSnapshot _visualization_state_snapshot;
void VisualizeRssResultsLocked(carla::client::DebugHelper &dh,
carla::client::World &world,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
::ad::rss::state::RssStateSnapshot state_snapshot) const;
void VisualizeRssResultsLocked(
carla::client::DebugHelper &dh, carla::client::World &world,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
::ad::rss::state::RssStateSnapshot state_snapshot) const;
/// the FullRoute to be visualized
std::pair<::ad::map::route::FullRoute, bool> _visualization_route;
void VisualizeRouteLocked(carla::client::DebugHelper &dh,
::ad::map::route::FullRoute const &route,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
bool dangerous) const;
void VisualizeRouteLocked(
carla::client::DebugHelper &dh, ::ad::map::route::FullRoute const &route,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
bool dangerous) const;
void VisualizeENUEdgeLocked(carla::client::DebugHelper &dh,
::ad::map::point::ENUEdge const &edge,
@ -292,12 +326,14 @@ private:
/// the EgoDynamicsOnRoute to be visualized
EgoDynamicsOnRoute _visualization_ego_dynamics;
void VisualizeEgoDynamics(carla::client::DebugHelper &dh,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
EgoDynamicsOnRoute const &ego_dynamics_on_route) const;
void VisualizeEgoDynamics(
carla::client::DebugHelper &dh,
carla::SharedPtr<carla::client::Actor> const &carla_ego_actor,
EgoDynamicsOnRoute const &ego_dynamics_on_route) const;
mutable ::ad::map::route::FullRoute _visualization_debug_route;
mutable std::vector<::ad::map::lane::ENUBorder> _visualization_debug_enu_border;
mutable std::vector<::ad::map::lane::ENUBorder>
_visualization_debug_enu_border;
};
} // namespace rss
@ -313,15 +349,21 @@ namespace std {
* \returns The stream object.
*
*/
inline std::ostream &operator<<(std::ostream &out, const ::carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route) {
inline std::ostream &operator<<(
std::ostream &out,
const ::carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route) {
out << "EgoDynamicsOnRoute(timestamp=" << ego_dynamics_on_route.timestamp
<< ", time_since_epoch_check_start_ms=" << ego_dynamics_on_route.time_since_epoch_check_start_ms
<< ", time_since_epoch_check_end_ms=" << ego_dynamics_on_route.time_since_epoch_check_end_ms
<< ", time_since_epoch_check_start_ms="
<< ego_dynamics_on_route.time_since_epoch_check_start_ms
<< ", time_since_epoch_check_end_ms="
<< ego_dynamics_on_route.time_since_epoch_check_end_ms
<< ", ego_speed=" << ego_dynamics_on_route.ego_speed
<< ", min_stopping_distance=" << ego_dynamics_on_route.min_stopping_distance
<< ", min_stopping_distance="
<< ego_dynamics_on_route.min_stopping_distance
<< ", ego_center=" << ego_dynamics_on_route.ego_center
<< ", ego_heading=" << ego_dynamics_on_route.ego_heading
<< ", ego_center_within_route=" << ego_dynamics_on_route.ego_center_within_route
<< ", ego_center_within_route="
<< ego_dynamics_on_route.ego_center_within_route
<< ", crossing_border=" << ego_dynamics_on_route.crossing_border
<< ", route_heading=" << ego_dynamics_on_route.route_heading
<< ", route_nominal_center=" << ego_dynamics_on_route.route_nominal_center
@ -335,4 +377,4 @@ inline std::ostream &operator<<(std::ostream &out, const ::carla::rss::EgoDynami
<< ')';
return out;
}
} // namespace std
} // namespace std

View File

@ -4,24 +4,22 @@
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "carla/rss/RssRestrictor.h"
#include "carla/rss/RssCheck.h"
#include "carla/rpc/VehicleControl.h"
#include "carla/rpc/VehiclePhysicsControl.h"
#include "carla/rss/RssCheck.h"
#include <spdlog/sinks/stdout_color_sinks.h>
#include <ad/rss/world/AccelerationRestriction.hpp>
#include <ad/rss/world/Velocity.hpp>
#include <spdlog/sinks/stdout_color_sinks.h>
namespace carla {
namespace rss {
RssRestrictor::RssRestrictor()
{
std::string loggerName = "RssRestrictor";
_logger = spdlog::get(loggerName);
if (!_logger)
{
_logger = spdlog::create<spdlog::sinks::stdout_color_sink_st>(loggerName);
RssRestrictor::RssRestrictor() {
std::string logger_name = "RssRestrictor";
_logger = spdlog::get(logger_name);
if (!_logger) {
_logger = spdlog::create<spdlog::sinks::stdout_color_sink_st>(logger_name);
}
//_logger->set_level(spdlog::level::debug);
}
@ -29,21 +27,23 @@ RssRestrictor::RssRestrictor()
RssRestrictor::~RssRestrictor() = default;
carla::rpc::VehicleControl RssRestrictor::RestrictVehicleControl(
const carla::rpc::VehicleControl &vehicle_control,
const ::ad::rss::world::AccelerationRestriction &restriction,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route,
const carla::rpc::VehiclePhysicsControl &vehicle_physics) {
const carla::rpc::VehicleControl &vehicle_control,
const ::ad::rss::world::AccelerationRestriction &restriction,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route,
const carla::rpc::VehiclePhysicsControl &vehicle_physics) {
carla::rpc::VehicleControl restricted_vehicle_control(vehicle_control);
// Pretty basic implementation of a RSS restrictor modifying the
// VehicleControl according to the given
// restrictions. Basic braking and countersteering actions are applied.
// In case countersteering is not possible anymore (i.e. the lateral velocity reached zero),
// as a fallback longitudinal braking is applied instead (escalation strategy).
// In case countersteering is not possible anymore (i.e. the lateral velocity
// reached zero),
// as a fallback longitudinal braking is applied instead (escalation
// strategy).
::ad::physics::Acceleration zero_accel(0.0);
float mass = vehicle_physics.mass;
float mass = vehicle_physics.mass;
float max_steer_angle_deg = 0.f;
float sum_max_brake_torque = 0.f;
float radius = 1.f;
@ -55,41 +55,60 @@ carla::rpc::VehicleControl RssRestrictor::RestrictVehicleControl(
// do not apply any restrictions when in reverse gear
if (!vehicle_control.reverse) {
_logger->debug("Lon {}, L {}, R {}; LatSpeed {}, Accel {}, Avg {}", restriction.longitudinalRange, restriction.lateralLeftRange, restriction.lateralRightRange, ego_dynamics_on_route.route_speed_lat, ego_dynamics_on_route.route_accel_lat, ego_dynamics_on_route.avg_route_accel_lat);
if (restriction.lateralLeftRange.maximum <= ::ad::physics::Acceleration(0.0)) {
_logger->debug("Lon {}, L {}, R {}; LatSpeed {}, Accel {}, Avg {}",
restriction.longitudinalRange, restriction.lateralLeftRange,
restriction.lateralRightRange,
ego_dynamics_on_route.route_speed_lat,
ego_dynamics_on_route.route_accel_lat,
ego_dynamics_on_route.avg_route_accel_lat);
if (restriction.lateralLeftRange.maximum <=
::ad::physics::Acceleration(0.0)) {
if (ego_dynamics_on_route.route_speed_lat < ::ad::physics::Speed(0.0)) {
// driving to the left
if (ego_dynamics_on_route.route_speed_lon != ::ad::physics::Speed(0.0)) {
double angle_rad = std::atan(ego_dynamics_on_route.route_speed_lat / ego_dynamics_on_route.route_speed_lon);
float desired_steer_ratio = -180.f * static_cast<float>(angle_rad / M_PI) / max_steer_angle_deg;
if ( ego_dynamics_on_route.crossing_border )
{
if (ego_dynamics_on_route.route_speed_lon !=
::ad::physics::Speed(0.0)) {
double angle_rad = std::atan(ego_dynamics_on_route.route_speed_lat /
ego_dynamics_on_route.route_speed_lon);
float desired_steer_ratio = -180.f *
static_cast<float>(angle_rad / M_PI) /
max_steer_angle_deg;
if (ego_dynamics_on_route.crossing_border) {
desired_steer_ratio += 0.1f;
}
float orig_steer = restricted_vehicle_control.steer;
restricted_vehicle_control.steer = std::max(restricted_vehicle_control.steer, desired_steer_ratio);
restricted_vehicle_control.steer = std::min(restricted_vehicle_control.steer, 1.0f);
restricted_vehicle_control.steer =
std::max(restricted_vehicle_control.steer, desired_steer_ratio);
restricted_vehicle_control.steer =
std::min(restricted_vehicle_control.steer, 1.0f);
_logger->debug("EgoVelocity: {}", ego_dynamics_on_route);
_logger->debug("Countersteer left to right: {} -> {}", orig_steer, restricted_vehicle_control.steer);
_logger->debug("Countersteer left to right: {} -> {}", orig_steer,
restricted_vehicle_control.steer);
}
}
}
if (restriction.lateralRightRange.maximum <= ::ad::physics::Acceleration(0.0)) {
if (restriction.lateralRightRange.maximum <=
::ad::physics::Acceleration(0.0)) {
if (ego_dynamics_on_route.route_speed_lat > ::ad::physics::Speed(0.0)) {
// driving to the right
if (ego_dynamics_on_route.route_speed_lon != ::ad::physics::Speed(0.0)) {
double angle_rad = std::atan(ego_dynamics_on_route.route_speed_lat / ego_dynamics_on_route.route_speed_lon);
float desired_steer_ratio = -180.f * static_cast<float>(angle_rad / M_PI) / max_steer_angle_deg;
if ( ego_dynamics_on_route.crossing_border )
{
if (ego_dynamics_on_route.route_speed_lon !=
::ad::physics::Speed(0.0)) {
double angle_rad = std::atan(ego_dynamics_on_route.route_speed_lat /
ego_dynamics_on_route.route_speed_lon);
float desired_steer_ratio = -180.f *
static_cast<float>(angle_rad / M_PI) /
max_steer_angle_deg;
if (ego_dynamics_on_route.crossing_border) {
desired_steer_ratio -= 0.1f;
}
float orig_steer = restricted_vehicle_control.steer;
restricted_vehicle_control.steer = std::min(restricted_vehicle_control.steer, desired_steer_ratio);
restricted_vehicle_control.steer = std::max(restricted_vehicle_control.steer, -1.0f);
restricted_vehicle_control.steer =
std::min(restricted_vehicle_control.steer, desired_steer_ratio);
restricted_vehicle_control.steer =
std::max(restricted_vehicle_control.steer, -1.0f);
_logger->debug("EgoVelocity: {}", ego_dynamics_on_route);
_logger->debug("Countersteer right to left: {} -> {}", orig_steer, restricted_vehicle_control.steer);
_logger->debug("Countersteer right to left: {} -> {}", orig_steer,
restricted_vehicle_control.steer);
}
}
}
@ -103,16 +122,20 @@ carla::rpc::VehicleControl RssRestrictor::RestrictVehicleControl(
if (restriction.longitudinalRange.maximum < zero_accel) {
restricted_vehicle_control.throttle = 0.0f;
double brake_acceleration = std::fabs(static_cast<double>(restriction.longitudinalRange.minimum));
double brake_acceleration =
std::fabs(static_cast<double>(restriction.longitudinalRange.minimum));
double sum_brake_torque = mass * brake_acceleration * radius / 100.0;
restricted_vehicle_control.brake = std::min(static_cast<float>(sum_brake_torque / sum_max_brake_torque), 1.0f);
restricted_vehicle_control.brake = std::min(
static_cast<float>(sum_brake_torque / sum_max_brake_torque), 1.0f);
}
}
if(restricted_vehicle_control != vehicle_control) {
_logger->debug("Restrictor active: throttle({} -> {}), brake ({} -> {}). steer ({} -> {})",
vehicle_control.throttle, restricted_vehicle_control.throttle,
vehicle_control.brake, restricted_vehicle_control.brake,
vehicle_control.steer, restricted_vehicle_control.steer);
if (restricted_vehicle_control != vehicle_control) {
_logger->debug(
"Restrictor active: throttle({} -> {}), brake ({} -> {}). steer ({} -> "
"{})",
vehicle_control.throttle, restricted_vehicle_control.throttle,
vehicle_control.brake, restricted_vehicle_control.brake,
vehicle_control.steer, restricted_vehicle_control.steer);
}
return restricted_vehicle_control;
}

View File

@ -5,10 +5,10 @@
#pragma once
#include <memory>
#include <spdlog/spdlog.h>
#include <memory>
namespace ad{
namespace ad {
namespace rss {
namespace world {
@ -27,27 +27,31 @@ class VehiclePhysicsControl;
namespace rss {
/// @brief forward declararion for ego vehicles current dynamics in respect to the current route
/// @brief forward declararion for ego vehicles current dynamics in respect to
/// the current route
struct EgoDynamicsOnRoute;
/// @brief class implementing the RSS restrictions within CARLA
class RssRestrictor {
public:
public:
/// @brief constructor
RssRestrictor();
/// @brief destructor
~RssRestrictor();
/// @brief the actual function to restrict the given vehicle control input to mimick
/// @brief the actual function to restrict the given vehicle control input to
/// mimick
/// RSS conform behavior by braking
/// Lateral braking is achieved by counter-steering, so is only a very rough solution
carla::rpc::VehicleControl RestrictVehicleControl(const carla::rpc::VehicleControl &vehicle_control,
const ::ad::rss::world::AccelerationRestriction &restriction,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route,
const carla::rpc::VehiclePhysicsControl &vehicle_physics);
/// Lateral braking is achieved by counter-steering, so is only a very
/// rough solution
carla::rpc::VehicleControl RestrictVehicleControl(
const carla::rpc::VehicleControl &vehicle_control,
const ::ad::rss::world::AccelerationRestriction &restriction,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route,
const carla::rpc::VehiclePhysicsControl &vehicle_physics);
private:
private:
/// @brief the logger instance
std::shared_ptr<spdlog::logger> _logger;
};

View File

@ -13,22 +13,20 @@
#include <fstream>
#include "carla/Logging.h"
#include "carla/client/Sensor.h"
#include "carla/client/Map.h"
#include "carla/client/Sensor.h"
#include "carla/client/detail/Simulator.h"
#include "carla/rss/RssCheck.h"
#include "carla/sensor/data/RssResponse.h"
namespace carla {
namespace client {
RssSensor::RssSensor(ActorInitializer init)
: Sensor(std::move(init))
, _on_tick_register_id(0u)
, _rss_check(std::make_shared<::carla::rss::RssCheck>())
, _drop_route(false) {
}
: Sensor(std::move(init)),
_on_tick_register_id(0u),
_rss_check(std::make_shared<::carla::rss::RssCheck>()),
_drop_route(false) {}
RssSensor::~RssSensor() = default;
@ -39,7 +37,8 @@ void RssSensor::Listen(CallbackFunctionType callback) {
}
if (GetParent() == nullptr) {
throw_exception(std::runtime_error(GetDisplayId() + ": not attached to vehicle"));
throw_exception(
std::runtime_error(GetDisplayId() + ": not attached to vehicle"));
return;
}
@ -49,23 +48,24 @@ void RssSensor::Listen(CallbackFunctionType callback) {
::ad::map::access::cleanup();
::ad::map::access::initFromOpenDriveContent(
open_drive_content, 0.2,
::ad::map::intersection::IntersectionType::TrafficLight,
::ad::map::landmark::TrafficLightType::LEFT_STRAIGHT_RED_YELLOW_GREEN);
open_drive_content, 0.2,
::ad::map::intersection::IntersectionType::TrafficLight,
::ad::map::landmark::TrafficLightType::LEFT_STRAIGHT_RED_YELLOW_GREEN);
auto self = boost::static_pointer_cast<RssSensor>(shared_from_this());
log_debug(GetDisplayId(), ": subscribing to tick event");
_on_tick_register_id = GetEpisode().Lock()->RegisterOnTickEvent(
[cb = std::move(callback), weak_self = WeakPtr<RssSensor>(self)](const auto &snapshot) {
auto self = weak_self.lock();
if (self != nullptr) {
auto data = self->TickRssSensor(snapshot.GetTimestamp());
if (data != nullptr) {
cb(std::move(data));
}
}
});
_on_tick_register_id = GetEpisode().Lock()->RegisterOnTickEvent([
cb = std::move(callback), weak_self = WeakPtr<RssSensor>(self)
](const auto &snapshot) {
auto self = weak_self.lock();
if (self != nullptr) {
auto data = self->TickRssSensor(snapshot.GetTimestamp());
if (data != nullptr) {
cb(std::move(data));
}
}
});
}
void RssSensor::Stop() {
@ -84,35 +84,42 @@ void RssSensor::Stop() {
::ad::map::access::cleanup();
}
const ::ad::rss::world::RssDynamics& RssSensor::GetEgoVehicleDynamics() const {
const ::ad::rss::world::RssDynamics &RssSensor::GetEgoVehicleDynamics() const {
return _rss_check->GetEgoVehicleDynamics();
}
void RssSensor::SetEgoVehicleDynamics(const ::ad::rss::world::RssDynamics &ego_dynamics) {
void RssSensor::SetEgoVehicleDynamics(
const ::ad::rss::world::RssDynamics &ego_dynamics) {
_rss_check->SetEgoVehicleDynamics(ego_dynamics);
}
const ::ad::rss::world::RssDynamics& RssSensor::GetOtherVehicleDynamics() const {
const ::ad::rss::world::RssDynamics &RssSensor::GetOtherVehicleDynamics()
const {
return _rss_check->GetOtherVehicleDynamics();
}
void RssSensor::SetOtherVehicleDynamics(const ::ad::rss::world::RssDynamics &other_vehicle_dynamics) {
void RssSensor::SetOtherVehicleDynamics(
const ::ad::rss::world::RssDynamics &other_vehicle_dynamics) {
_rss_check->SetOtherVehicleDynamics(other_vehicle_dynamics);
}
const ::carla::rss::RoadBoundariesMode& RssSensor::GetRoadBoundariesMode() const {
const ::carla::rss::RoadBoundariesMode &RssSensor::GetRoadBoundariesMode()
const {
return _rss_check->GetRoadBoundariesMode();
}
void RssSensor::SetRoadBoundariesMode(const ::carla::rss::RoadBoundariesMode &road_boundaries_mode) {
void RssSensor::SetRoadBoundariesMode(
const ::carla::rss::RoadBoundariesMode &road_boundaries_mode) {
_rss_check->SetRoadBoundariesMode(road_boundaries_mode);
}
void RssSensor::AppendRoutingTarget(const ::carla::geom::Transform &routing_target) {
void RssSensor::AppendRoutingTarget(
const ::carla::geom::Transform &routing_target) {
_rss_check->AppendRoutingTarget(routing_target);
}
const std::vector<::carla::geom::Transform> RssSensor::GetRoutingTargets() const {
const std::vector<::carla::geom::Transform> RssSensor::GetRoutingTargets()
const {
return _rss_check->GetRoutingTargets();
}
@ -120,21 +127,23 @@ void RssSensor::ResetRoutingTargets() {
_rss_check->ResetRoutingTargets();
}
void RssSensor::SetVisualizationMode(const ::carla::rss::VisualizationMode &visualization_mode) {
void RssSensor::SetVisualizationMode(
const ::carla::rss::VisualizationMode &visualization_mode) {
_rss_check->SetVisualizationMode(visualization_mode);
}
const ::carla::rss::VisualizationMode& RssSensor::GetVisualizationMode() const {
const ::carla::rss::VisualizationMode &RssSensor::GetVisualizationMode() const {
return _rss_check->GetVisualizationMode();
}
void RssSensor::DropRoute() {
// don't execute this immediately as it might break calculations completely
// postpone to next sensor tick
_drop_route=true;
_drop_route = true;
}
SharedPtr<sensor::SensorData> RssSensor::TickRssSensor(const Timestamp &timestamp) {
SharedPtr<sensor::SensorData> RssSensor::TickRssSensor(
const Timestamp &timestamp) {
try {
bool result = false;
::ad::rss::state::ProperResponse response;
@ -146,24 +155,29 @@ SharedPtr<sensor::SensorData> RssSensor::TickRssSensor(const Timestamp &timestam
carla::client::World world = GetWorld();
SharedPtr<carla::client::ActorList> actors = world.GetActors();
if ( _drop_route )
{
_drop_route=false;
if (_drop_route) {
_drop_route = false;
_rss_check->DropRoute();
}
// check all object<->ego pairs with RSS and calculate proper response
result = _rss_check->CheckObjects(timestamp, actors, GetParent(), response, acceleration_restriction, rss_state_snapshot,
ego_dynamics_on_route);
result = _rss_check->CheckObjects(
timestamp, actors, GetParent(), response, acceleration_restriction,
rss_state_snapshot, ego_dynamics_on_route);
_processing_lock.unlock();
_rss_check->VisualizeResults(world, GetParent());
spdlog::debug("RssSensor response: T={} S:{}->E:{} DeltaT:{}", timestamp.frame, ego_dynamics_on_route.time_since_epoch_check_start_ms,
spdlog::debug("RssSensor response: T={} S:{}->E:{} DeltaT:{}",
timestamp.frame,
ego_dynamics_on_route.time_since_epoch_check_start_ms,
ego_dynamics_on_route.time_since_epoch_check_end_ms,
ego_dynamics_on_route.time_since_epoch_check_end_ms-ego_dynamics_on_route.time_since_epoch_check_start_ms);
return MakeShared<sensor::data::RssResponse>(timestamp.frame, timestamp.elapsed_seconds, GetTransform(),
result, response, acceleration_restriction, rss_state_snapshot, ego_dynamics_on_route);
ego_dynamics_on_route.time_since_epoch_check_end_ms -
ego_dynamics_on_route.time_since_epoch_check_start_ms);
return MakeShared<sensor::data::RssResponse>(
timestamp.frame, timestamp.elapsed_seconds, GetTransform(), result,
response, acceleration_restriction, rss_state_snapshot,
ego_dynamics_on_route);
} else {
spdlog::debug("RssSensor tick dropped: T={}", timestamp.frame);
return nullptr;
@ -172,11 +186,11 @@ SharedPtr<sensor::SensorData> RssSensor::TickRssSensor(const Timestamp &timestam
/// @todo do we need to unsubscribe the sensor here?
std::cout << e.what() << std::endl;
_processing_lock.unlock();
spdlog::error("RssSensor tick exception");
spdlog::error("RssSensor tick exception");
return nullptr;
} catch (...) {
_processing_lock.unlock();
spdlog::error("RssSensor tick exception");
spdlog::error("RssSensor tick exception");
return nullptr;
}
}

View File

@ -17,9 +17,9 @@ namespace world {
/// forward declaration of the RssDynamics struct
struct RssDynamics;
} //namespace world
} //namespace rss
} // namespace ad
} // namespace world
} // namespace rss
} // namespace ad
namespace carla {
@ -32,14 +32,14 @@ enum class VisualizationMode;
/// forward declaration of the RssCheck class
class RssCheck;
} //namespace rss
} // namespace rss
namespace client {
/// The RSS Sensor class implementing the carla::client::Sensor interface
/// This class is a proxy to the RssCheck class
class RssSensor : public Sensor {
public:
public:
using Sensor::Sensor;
/// @brief constructor
@ -62,47 +62,63 @@ class RssSensor : public Sensor {
/// Return whether this Sensor instance is currently listening to the
/// associated sensor in the simulator.
bool IsListening() const override { return _on_tick_register_id != 0u; }
bool IsListening() const override {
return _on_tick_register_id != 0u;
}
/// @returns the currently used dynamics of the ego vehicle (@see also RssCheck::GetEgoVehicleDynamics())
const ::ad::rss::world::RssDynamics& GetEgoVehicleDynamics() const;
/// @brief sets the ego vehicle dynamics to be used by the ego vehicle (@see also RssCheck::SetEgoVehicleDynamics())
/// @returns the currently used dynamics of the ego vehicle (@see also
/// RssCheck::GetEgoVehicleDynamics())
const ::ad::rss::world::RssDynamics &GetEgoVehicleDynamics() const;
/// @brief sets the ego vehicle dynamics to be used by the ego vehicle (@see
/// also RssCheck::SetEgoVehicleDynamics())
void SetEgoVehicleDynamics(const ::ad::rss::world::RssDynamics &ego_dynamics);
/// @returns the currently used dynamics of other vehicles (@see also RssCheck::GetOtherVehicleDynamics())
const ::ad::rss::world::RssDynamics& GetOtherVehicleDynamics() const;
/// @brief sets the ego vehicle dynamics to be used by other vehicles (@see also RssCheck::SetOtherVehicleDynamics())
void SetOtherVehicleDynamics(const ::ad::rss::world::RssDynamics &other_vehicle_dynamics);
/// @returns the currently used dynamics of other vehicles (@see also
/// RssCheck::GetOtherVehicleDynamics())
const ::ad::rss::world::RssDynamics &GetOtherVehicleDynamics() const;
/// @brief sets the ego vehicle dynamics to be used by other vehicles (@see
/// also RssCheck::SetOtherVehicleDynamics())
void SetOtherVehicleDynamics(
const ::ad::rss::world::RssDynamics &other_vehicle_dynamics);
/// @returns the current mode for respecting the road boundaries (@see also RssCheck::GetRoadBoundariesMode())
const ::carla::rss::RoadBoundariesMode& GetRoadBoundariesMode() const;
/// @brief sets the current mode for respecting the road boundaries (@see also RssCheck::SetRoadBoundariesMode())
void SetRoadBoundariesMode(const ::carla::rss::RoadBoundariesMode &road_boundaries_mode);
/// @returns the current mode for respecting the road boundaries (@see also
/// RssCheck::GetRoadBoundariesMode())
const ::carla::rss::RoadBoundariesMode &GetRoadBoundariesMode() const;
/// @brief sets the current mode for respecting the road boundaries (@see also
/// RssCheck::SetRoadBoundariesMode())
void SetRoadBoundariesMode(
const ::carla::rss::RoadBoundariesMode &road_boundaries_mode);
/// @returns the current routing targets (@see also RssCheck::GetRoutingTargets())
/// @returns the current routing targets (@see also
/// RssCheck::GetRoutingTargets())
const std::vector<::carla::geom::Transform> GetRoutingTargets() const;
/// @brief appends a routing target to the current routing target list (@see also RssCheck::AppendRoutingTarget())
/// @brief appends a routing target to the current routing target list (@see
/// also RssCheck::AppendRoutingTarget())
void AppendRoutingTarget(const ::carla::geom::Transform &routing_target);
/// @brief resets the current routing target (@see also RssCheck::ResetRoutingTargets())
/// @brief resets the current routing target (@see also
/// RssCheck::ResetRoutingTargets())
void ResetRoutingTargets();
/// @brief sets the visualization mode (@see also RssCheck::SetVisualizationMode())
void SetVisualizationMode(const ::carla::rss::VisualizationMode &visualization_mode);
/// @returns get the current visualization mode (@see also RssCheck::GetVisualizationMode())
const ::carla::rss::VisualizationMode& GetVisualizationMode() const;
/// @brief sets the visualization mode (@see also
/// RssCheck::SetVisualizationMode())
void SetVisualizationMode(
const ::carla::rss::VisualizationMode &visualization_mode);
/// @returns get the current visualization mode (@see also
/// RssCheck::GetVisualizationMode())
const ::carla::rss::VisualizationMode &GetVisualizationMode() const;
/// @brief drop the current route (@see also RssCheck::DropRoute())
void DropRoute();
private:
/// the acutal sensor tick callback function
SharedPtr<sensor::SensorData> TickRssSensor(const Timestamp &timestamp);
/// the id got when registering for the on tick event
std::size_t _on_tick_register_id;
/// the mutex to protect the actual RSS processing and decouple the (slow) visualization
/// the mutex to protect the actual RSS processing and decouple the (slow)
/// visualization
std::mutex _processing_lock;
//// the object actually performing the RSS processing

View File

@ -5,69 +5,66 @@
#pragma once
#include "carla/sensor/SensorData.h"
#include "carla/rss/RssCheck.h"
#include "carla/sensor/SensorData.h"
namespace carla {
namespace sensor {
namespace data {
/// A RSS Response
class RssResponse : public SensorData {
public:
/// A RSS Response
class RssResponse : public SensorData {
public:
explicit RssResponse(
size_t frame_number, double timestamp,
const rpc::Transform &sensor_transform, const bool &response_valid,
const ::ad::rss::state::ProperResponse &response,
const ::ad::rss::world::AccelerationRestriction &acceleration_restriction,
const ::ad::rss::state::RssStateSnapshot &rss_state_snapshot,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route)
: SensorData(frame_number, timestamp, sensor_transform),
_response_valid(response_valid),
_response(response),
_acceleration_restriction(acceleration_restriction),
_rss_state_snapshot(rss_state_snapshot),
_ego_dynamics_on_route(ego_dynamics_on_route) {}
explicit RssResponse(
size_t frame_number,
double timestamp,
const rpc::Transform &sensor_transform,
const bool &response_valid,
const ::ad::rss::state::ProperResponse &response,
const ::ad::rss::world::AccelerationRestriction &acceleration_restriction,
const ::ad::rss::state::RssStateSnapshot &rss_state_snapshot,
const carla::rss::EgoDynamicsOnRoute &ego_dynamics_on_route)
: SensorData(frame_number, timestamp, sensor_transform),
_response_valid(response_valid),
_response(response),
_acceleration_restriction(acceleration_restriction),
_rss_state_snapshot(rss_state_snapshot),
_ego_dynamics_on_route(ego_dynamics_on_route){}
bool GetResponseValid() const {
return _response_valid;
}
bool GetResponseValid() const {
return _response_valid;
}
const ::ad::rss::state::ProperResponse &GetProperResponse() const {
return _response;
}
const ::ad::rss::state::ProperResponse &GetProperResponse() const {
return _response;
}
const ::ad::rss::world::AccelerationRestriction &GetAccelerationRestriction()
const {
return _acceleration_restriction;
}
const ::ad::rss::world::AccelerationRestriction &GetAccelerationRestriction() const {
return _acceleration_restriction;
}
const ::ad::rss::state::RssStateSnapshot &GetRssStateSnapshot() const {
return _rss_state_snapshot;
}
const ::ad::rss::state::RssStateSnapshot &GetRssStateSnapshot() const {
return _rss_state_snapshot;
}
const carla::rss::EgoDynamicsOnRoute &GetEgoDynamicsOnRoute() const {
return _ego_dynamics_on_route;
}
const carla::rss::EgoDynamicsOnRoute &GetEgoDynamicsOnRoute() const {
return _ego_dynamics_on_route;
}
private:
/*!
* The validity of RSS calculation.
*/
bool _response_valid;
private:
::ad::rss::state::ProperResponse _response;
/*!
* The validity of RSS calculation.
*/
bool _response_valid;
::ad::rss::world::AccelerationRestriction _acceleration_restriction;
::ad::rss::state::ProperResponse _response;
::ad::rss::state::RssStateSnapshot _rss_state_snapshot;
::ad::rss::world::AccelerationRestriction _acceleration_restriction;
carla::rss::EgoDynamicsOnRoute _ego_dynamics_on_route;
};
::ad::rss::state::RssStateSnapshot _rss_state_snapshot;
carla::rss::EgoDynamicsOnRoute _ego_dynamics_on_route;
};
} // namespace data
} // namespace sensor
} // namespace carla
} // namespace data
} // namespace sensor
} // namespace carla

View File

@ -3,8 +3,8 @@
// This work is licensed under the terms of the MIT license.
// For a copy, see <https://opensource.org/licenses/MIT>.
#include <carla/rss/RssSensor.h>
#include <carla/rss/RssRestrictor.h>
#include <carla/rss/RssSensor.h>
#include <carla/sensor/data/RssResponse.h>
#include <ad/rss/world/RssDynamics.hpp>
@ -12,46 +12,45 @@
#ifdef LIBCARLA_PYTHON_MAJOR_2
extern "C" {
void initlibad_physics_python();
void initlibad_rss_python();
void initlibad_map_access_python();
void initlibad_rss_map_integration_python();
void initlibad_physics_python();
void initlibad_rss_python();
void initlibad_map_access_python();
void initlibad_rss_map_integration_python();
}
#endif
#ifdef LIBCARLA_PYTHON_MAJOR_3
extern "C" {
void PyInit_libad_physics_python();
void PyInit_libad_rss_python();
void PyInit_libad_map_access_python();
void PyInit_libad_rss_map_integration_python();
void PyInit_libad_physics_python();
void PyInit_libad_rss_python();
void PyInit_libad_map_access_python();
void PyInit_libad_rss_map_integration_python();
}
#endif
namespace carla {
namespace rss {
std::ostream &operator<<(std::ostream &out, const RssRestrictor &) {
out << "RssRestrictor()";
return out;
}
std::ostream &operator<<(std::ostream &out, const RssRestrictor &) {
out << "RssRestrictor()";
return out;
}
} // namespace rss
} // namespace rss
namespace sensor {
namespace data {
std::ostream &operator<<(std::ostream &out, const RssResponse &resp) {
out << "RssResponse(frame=" << resp.GetFrame()
<< ", timestamp=" << resp.GetTimestamp()
<< ", valid=" << resp.GetResponseValid()
<< ')';
return out;
}
std::ostream &operator<<(std::ostream &out, const RssResponse &resp) {
out << "RssResponse(frame=" << resp.GetFrame()
<< ", timestamp=" << resp.GetTimestamp()
<< ", valid=" << resp.GetResponseValid() << ')';
return out;
}
} // namespace data
} // namespace sensor
} // namespace carla
} // namespace data
} // namespace sensor
} // namespace carla
static auto GetEgoVehicleDynamics(const carla::client::RssSensor &self) {
ad::rss::world::RssDynamics ego_dynamics(self.GetEgoVehicleDynamics());
@ -64,7 +63,8 @@ static auto GetOtherVehicleDynamics(const carla::client::RssSensor &self) {
}
static auto GetRoadBoundariesMode(const carla::client::RssSensor &self) {
carla::rss::RoadBoundariesMode road_boundaries_mode(self.GetRoadBoundariesMode());
carla::rss::RoadBoundariesMode road_boundaries_mode(
self.GetRoadBoundariesMode());
return road_boundaries_mode;
}
@ -79,7 +79,6 @@ static auto GetVisualizationMode(const carla::client::RssSensor &self) {
}
void export_ad_rss() {
#ifdef LIBCARLA_PYTHON_MAJOR_2
initlibad_physics_python();
initlibad_rss_python();
@ -94,73 +93,98 @@ void export_ad_rss() {
PyInit_libad_rss_map_integration_python();
#endif
using namespace boost::python;
namespace cc = carla::client;
namespace cs = carla::sensor;
namespace csd = carla::sensor::data;
class_<carla::rss::EgoDynamicsOnRoute>("EgoDynamicsOnRoute")
.def_readwrite("timestamp", &carla::rss::EgoDynamicsOnRoute::timestamp)
.def_readwrite("time_since_epoch_check_start_ms", &carla::rss::EgoDynamicsOnRoute::time_since_epoch_check_start_ms)
.def_readwrite("time_since_epoch_check_end_ms", &carla::rss::EgoDynamicsOnRoute::time_since_epoch_check_end_ms)
.def_readwrite("ego_speed", &carla::rss::EgoDynamicsOnRoute::ego_speed)
.def_readwrite("min_stopping_distance", &carla::rss::EgoDynamicsOnRoute::min_stopping_distance)
.def_readwrite("ego_center", &carla::rss::EgoDynamicsOnRoute::ego_center)
.def_readwrite("ego_heading", &carla::rss::EgoDynamicsOnRoute::ego_heading)
.def_readwrite("ego_center_within_route", &carla::rss::EgoDynamicsOnRoute::ego_center_within_route)
.def_readwrite("crossing_border", &carla::rss::EgoDynamicsOnRoute::crossing_border)
.def_readwrite("route_heading", &carla::rss::EgoDynamicsOnRoute::route_heading)
.def_readwrite("route_nominal_center", &carla::rss::EgoDynamicsOnRoute::route_nominal_center)
.def_readwrite("heading_diff", &carla::rss::EgoDynamicsOnRoute::heading_diff)
.def_readwrite("route_speed_lat", &carla::rss::EgoDynamicsOnRoute::route_speed_lat)
.def_readwrite("route_speed_lon", &carla::rss::EgoDynamicsOnRoute::route_speed_lon)
.def_readwrite("route_accel_lat", &carla::rss::EgoDynamicsOnRoute::route_accel_lat)
.def_readwrite("route_accel_lon", &carla::rss::EgoDynamicsOnRoute::route_accel_lon)
.def_readwrite("avg_route_accel_lat", &carla::rss::EgoDynamicsOnRoute::avg_route_accel_lat)
.def_readwrite("avg_route_accel_lon", &carla::rss::EgoDynamicsOnRoute::avg_route_accel_lon)
.def(self_ns::str(self_ns::self))
;
.def_readwrite("timestamp", &carla::rss::EgoDynamicsOnRoute::timestamp)
.def_readwrite(
"time_since_epoch_check_start_ms",
&carla::rss::EgoDynamicsOnRoute::time_since_epoch_check_start_ms)
.def_readwrite(
"time_since_epoch_check_end_ms",
&carla::rss::EgoDynamicsOnRoute::time_since_epoch_check_end_ms)
.def_readwrite("ego_speed", &carla::rss::EgoDynamicsOnRoute::ego_speed)
.def_readwrite("min_stopping_distance",
&carla::rss::EgoDynamicsOnRoute::min_stopping_distance)
.def_readwrite("ego_center", &carla::rss::EgoDynamicsOnRoute::ego_center)
.def_readwrite("ego_heading",
&carla::rss::EgoDynamicsOnRoute::ego_heading)
.def_readwrite("ego_center_within_route",
&carla::rss::EgoDynamicsOnRoute::ego_center_within_route)
.def_readwrite("crossing_border",
&carla::rss::EgoDynamicsOnRoute::crossing_border)
.def_readwrite("route_heading",
&carla::rss::EgoDynamicsOnRoute::route_heading)
.def_readwrite("route_nominal_center",
&carla::rss::EgoDynamicsOnRoute::route_nominal_center)
.def_readwrite("heading_diff",
&carla::rss::EgoDynamicsOnRoute::heading_diff)
.def_readwrite("route_speed_lat",
&carla::rss::EgoDynamicsOnRoute::route_speed_lat)
.def_readwrite("route_speed_lon",
&carla::rss::EgoDynamicsOnRoute::route_speed_lon)
.def_readwrite("route_accel_lat",
&carla::rss::EgoDynamicsOnRoute::route_accel_lat)
.def_readwrite("route_accel_lon",
&carla::rss::EgoDynamicsOnRoute::route_accel_lon)
.def_readwrite("avg_route_accel_lat",
&carla::rss::EgoDynamicsOnRoute::avg_route_accel_lat)
.def_readwrite("avg_route_accel_lon",
&carla::rss::EgoDynamicsOnRoute::avg_route_accel_lon)
.def(self_ns::str(self_ns::self));
enum_<carla::rss::RoadBoundariesMode>("RoadBoundariesMode")
.value("Off", carla::rss::RoadBoundariesMode::Off)
.value("On", carla::rss::RoadBoundariesMode::On)
;
.value("Off", carla::rss::RoadBoundariesMode::Off)
.value("On", carla::rss::RoadBoundariesMode::On);
enum_<carla::rss::VisualizationMode>("VisualizationMode")
.value("Off", carla::rss::VisualizationMode::Off)
.value("RouteOnly", carla::rss::VisualizationMode::RouteOnly)
.value("VehicleStateOnly", carla::rss::VisualizationMode::VehicleStateOnly)
.value("VehicleStateAndRoute", carla::rss::VisualizationMode::VehicleStateAndRoute)
.value("All", carla::rss::VisualizationMode::All)
;
.value("Off", carla::rss::VisualizationMode::Off)
.value("RouteOnly", carla::rss::VisualizationMode::RouteOnly)
.value("VehicleStateOnly",
carla::rss::VisualizationMode::VehicleStateOnly)
.value("VehicleStateAndRoute",
carla::rss::VisualizationMode::VehicleStateAndRoute)
.value("All", carla::rss::VisualizationMode::All);
class_<csd::RssResponse, bases<cs::SensorData>, boost::noncopyable, boost::shared_ptr<csd::RssResponse>>("RssResponse", no_init)
.add_property("response_valid", &csd::RssResponse::GetResponseValid)
.add_property("proper_response", CALL_RETURNING_COPY(csd::RssResponse, GetProperResponse))
.add_property("acceleration_restriction", CALL_RETURNING_COPY(csd::RssResponse, GetAccelerationRestriction))
.add_property("rss_state_snapshot", CALL_RETURNING_COPY(csd::RssResponse, GetRssStateSnapshot))
.add_property("ego_dynamics_on_route", CALL_RETURNING_COPY(csd::RssResponse, GetEgoDynamicsOnRoute))
.def(self_ns::str(self_ns::self))
;
class_<csd::RssResponse, bases<cs::SensorData>, boost::noncopyable,
boost::shared_ptr<csd::RssResponse>>("RssResponse", no_init)
.add_property("response_valid", &csd::RssResponse::GetResponseValid)
.add_property("proper_response",
CALL_RETURNING_COPY(csd::RssResponse, GetProperResponse))
.add_property(
"acceleration_restriction",
CALL_RETURNING_COPY(csd::RssResponse, GetAccelerationRestriction))
.add_property("rss_state_snapshot",
CALL_RETURNING_COPY(csd::RssResponse, GetRssStateSnapshot))
.add_property(
"ego_dynamics_on_route",
CALL_RETURNING_COPY(csd::RssResponse, GetEgoDynamicsOnRoute))
.def(self_ns::str(self_ns::self));
class_<cc::RssSensor, bases<cc::Sensor>, boost::noncopyable, boost::shared_ptr<cc::RssSensor>>
("RssSensor", no_init)
.add_property("ego_vehicle_dynamics", &GetEgoVehicleDynamics, &cc::RssSensor::SetEgoVehicleDynamics)
.add_property("other_vehicle_dynamics", &GetOtherVehicleDynamics, &cc::RssSensor::SetOtherVehicleDynamics)
.add_property("road_boundaries_mode", &GetRoadBoundariesMode, &cc::RssSensor::SetRoadBoundariesMode)
.add_property("visualization_mode", &GetVisualizationMode, &cc::RssSensor::SetVisualizationMode)
.add_property("routing_targets", &GetRoutingTargets)
.def("append_routing_target", &cc::RssSensor::AppendRoutingTarget)
.def("reset_routing_targets", &cc::RssSensor::ResetRoutingTargets)
.def("drop_route", &cc::RssSensor::DropRoute)
.def(self_ns::str(self_ns::self))
;
class_<cc::RssSensor, bases<cc::Sensor>, boost::noncopyable,
boost::shared_ptr<cc::RssSensor>>("RssSensor", no_init)
.add_property("ego_vehicle_dynamics", &GetEgoVehicleDynamics,
&cc::RssSensor::SetEgoVehicleDynamics)
.add_property("other_vehicle_dynamics", &GetOtherVehicleDynamics,
&cc::RssSensor::SetOtherVehicleDynamics)
.add_property("road_boundaries_mode", &GetRoadBoundariesMode,
&cc::RssSensor::SetRoadBoundariesMode)
.add_property("visualization_mode", &GetVisualizationMode,
&cc::RssSensor::SetVisualizationMode)
.add_property("routing_targets", &GetRoutingTargets)
.def("append_routing_target", &cc::RssSensor::AppendRoutingTarget)
.def("reset_routing_targets", &cc::RssSensor::ResetRoutingTargets)
.def("drop_route", &cc::RssSensor::DropRoute)
.def(self_ns::str(self_ns::self));
class_<carla::rss::RssRestrictor, boost::noncopyable, boost::shared_ptr<carla::rss::RssRestrictor>>
("RssRestrictor", no_init)
.def(init<>())
.def("restrict_vehicle_control", &carla::rss::RssRestrictor::RestrictVehicleControl, (arg("restriction"), arg("vehicleControl")))
.def(self_ns::str(self_ns::self))
;
class_<carla::rss::RssRestrictor, boost::noncopyable,
boost::shared_ptr<carla::rss::RssRestrictor>>("RssRestrictor", no_init)
.def(init<>())
.def("restrict_vehicle_control",
&carla::rss::RssRestrictor::RestrictVehicleControl,
(arg("restriction"), arg("vehicleControl")))
.def(self_ns::str(self_ns::self));
}

View File

@ -176,7 +176,7 @@ void export_geom() {
.def(self_ns::str(self_ns::self))
;
class_<std::vector<cg::Transform>>("vector_of_Transform")
class_<std::vector<cg::Transform>>("vector_of_transform")
.def(boost::python::vector_indexing_suite<std::vector<cg::Transform>>())
.def(self_ns::str(self_ns::self))
;

View File

@ -0,0 +1,95 @@
---
Language: Cpp
# BasedOnStyle: Google
AccessModifierOffset: -2
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: false
AlignConsecutiveDeclarations: false
AlignEscapedNewlinesLeft: true
AlignOperands: true
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: true
AllowShortBlocksOnASingleLine: false
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: Empty
AllowShortIfStatementsOnASingleLine: true
AllowShortLoopsOnASingleLine: true
AlwaysBreakAfterDefinitionReturnType: None
AlwaysBreakAfterReturnType: None
AlwaysBreakBeforeMultilineStrings: true
AlwaysBreakTemplateDeclarations: true
BinPackArguments: true
BinPackParameters: true
BraceWrapping:
AfterClass: false
AfterControlStatement: false
AfterEnum: false
AfterFunction: false
AfterNamespace: false
AfterObjCDeclaration: false
AfterStruct: false
AfterUnion: false
BeforeCatch: false
BeforeElse: false
IndentBraces: false
BreakBeforeBinaryOperators: None
BreakBeforeBraces: Attach
BreakBeforeTernaryOperators: true
BreakConstructorInitializersBeforeComma: false
BreakAfterJavaFieldAnnotations: false
BreakStringLiterals: true
ColumnLimit: 80
CommentPragmas: '^ IWYU pragma:'
ConstructorInitializerAllOnOneLineOrOnePerLine: true
ConstructorInitializerIndentWidth: 2
ContinuationIndentWidth: 4
Cpp11BracedListStyle: true
DerivePointerAlignment: true
DisableFormat: false
ExperimentalAutoDetectBinPacking: false
ForEachMacros: [ foreach, Q_FOREACH, BOOST_FOREACH ]
IncludeCategories:
- Regex: '^<.*\.h>'
Priority: 1
- Regex: '^<.*'
Priority: 2
- Regex: '.*'
Priority: 3
IncludeIsMainRegex: '([-_](test|unittest))?$'
IndentCaseLabels: true
IndentWidth: 2
IndentWrappedFunctionNames: false
JavaScriptQuotes: Leave
JavaScriptWrapImports: true
KeepEmptyLinesAtTheStartOfBlocks: false
MacroBlockBegin: ''
MacroBlockEnd: ''
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCBlockIndentWidth: 2
ObjCSpaceAfterProperty: false
ObjCSpaceBeforeProtocolList: false
PenaltyBreakBeforeFirstCallParameter: 1
PenaltyBreakComment: 300
PenaltyBreakFirstLessLess: 120
PenaltyBreakString: 1000
PenaltyExcessCharacter: 1000000
PenaltyReturnTypeOnItsOwnLine: 200
PointerAlignment: Left
ReflowComments: true
SortIncludes: true
SpaceAfterCStyleCast: false
SpaceBeforeAssignmentOperators: true
SpaceBeforeParens: ControlStatements
SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 2
SpacesInAngles: false
SpacesInContainerLiterals: true
SpacesInCStyleCastParentheses: false
SpacesInParentheses: false
SpacesInSquareBrackets: false
Standard: Auto
TabWidth: 8
UseTab: Never
...

429
Util/Formatting/codeformat.py Executable file
View File

@ -0,0 +1,429 @@
#!/usr/bin/python
#
# Copyright (c) 2017-2020 Intel Corporation
#
# Helper script for code formatting using clang-format-3.9 and autopep
import argparse
import filecmp
import os
import re
import sets
import subprocess
import sys
from termcolor import cprint
SCRIPT_VERSION = "1.3"
class CodeFormatter:
def __init__(self, command, expectedVersion, formatCommandArguments, verifyCommandArguments, verifyOutputIsDiff, fileEndings, fileDescription, installCommand):
self.command = command
self.expectedVersion = expectedVersion
self.formatCommandArguments = formatCommandArguments
self.verifyCommandArguments = verifyCommandArguments
self.verifyOutputIsDiff = verifyOutputIsDiff
self.fileEndings = fileEndings
self.fileDescription = fileDescription
self.installCommand = installCommand
def verifyFormatterVersion(self):
try:
versionOutput = subprocess.check_output([self.command, "--version"]).rstrip('\r\n')
if self.expectedVersion != "":
if versionOutput.startswith(self.expectedVersion):
print("[OK] Found formatter '" + versionOutput + "'")
return
else:
cprint("[NOT OK] Found '" + versionOutput + "'", "red")
cprint("[NOT OK] Version string does not start with '" + self.expectedVersion + "'", "red")
else:
return
except:
cprint("[ERROR] Could not run " + self.command, "red")
cprint("[INFO] Please check if correct version is installed or install with '" +
self.installCommand + "'", "blue")
sys.exit(1)
def printInputFiles(self):
if len(self.inputFiles) > 0:
print("Found " + self.fileDescription + " files:")
for fileName in self.inputFiles:
print(fileName)
print("")
def formatFile(self, fileName):
commandList = [self.command]
commandList.extend(self.formatCommandArguments)
commandList.append(fileName)
try:
subprocess.check_output(commandList, stderr=subprocess.STDOUT)
print("[OK] " + fileName)
except subprocess.CalledProcessError as e:
cprint("[ERROR] " + fileName + " (" + e.output.rstrip('\r\n') + ")", "red")
return True
return False
def performGitDiff(self, fileName, verifyOutput):
try:
diffProcess = subprocess.Popen(
["git", "diff", "--color=always", "--exit-code", "--no-index", "--", fileName, "-"],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE)
diffOutput, _ = diffProcess.communicate(verifyOutput)
if diffProcess.returncode == 0:
diffOutput = ""
except OSError:
cprint("[ERROR] Failed to run git diff on " + fileName, "red")
return (True, "")
return (False, diffOutput)
def verifyFile(self, fileName, printDiff):
commandList = [self.command]
commandList.extend(self.verifyCommandArguments)
commandList.append(fileName)
try:
verifyOutput = subprocess.check_output(commandList, stderr=subprocess.STDOUT)
except subprocess.CalledProcessError as e:
cprint("[ERROR] " + fileName + " (" + e.output.rstrip('\r\n') + ")", "red")
return True
diffOutput = ""
if self.verifyOutputIsDiff:
diffOutput = verifyOutput
else:
status, diffOutput = self.performGitDiff(fileName, verifyOutput)
if status:
return True
if diffOutput != "":
cprint("[NOT OK] " + fileName, "red")
if printDiff:
print(diffOutput.rstrip('\r\n'))
return True
print("[OK] " + fileName)
return False
class CodeFormatterClang(CodeFormatter):
CLANG_FORMAT_FILE = ".clang-format"
CHECKED_IN_CLANG_FORMAT_FILE = "clang-format"
CODE_FORMAT_IGNORE_FILE = ".codeformatignore"
def __init__(self):
CodeFormatter.__init__(self,
command="clang-format-3.9",
expectedVersion="clang-format version 3.9",
formatCommandArguments=["-style=file", "-fallback-style=none", "-i"],
verifyCommandArguments=["-style=file", "-fallback-style=none"],
verifyOutputIsDiff=False,
fileEndings=["cpp", "hpp", "c", "h", "cc"],
fileDescription="source and header",
installCommand="sudo apt-get install clang-format-3.9")
self.scriptPath = os.path.dirname(os.path.abspath(__file__))
self.checkedInClangFormatFile = os.path.join(self.scriptPath, CodeFormatterClang.CHECKED_IN_CLANG_FORMAT_FILE)
def verifyFormatterVersion(self):
CodeFormatter.verifyFormatterVersion(self)
self.verifyClangFormatFileExistsAndMatchesCheckedIn()
def verifyCheckedInClangFormatFileExists(self):
if os.path.exists(self.checkedInClangFormatFile):
print("[OK] Found " + CodeFormatterClang.CHECKED_IN_CLANG_FORMAT_FILE + " file (the one that should be in a repository) " +
self.checkedInClangFormatFile)
else:
cprint("[WARN] Not found " + CodeFormatterClang.CHECKED_IN_CLANG_FORMAT_FILE + " file " +
self.checkedInClangFormatFile, "yellow")
self.confirmWithUserClangFormatFileCantBeVerified()
def confirmWithUserClangFormatFileCantBeVerified(self):
if not self.args.yes:
answer = raw_input("Are you sure your .clang-format file is up-to-date and you want to continue? (y/N)")
if answer != "y":
sys.exit(1)
def verifyClangFormatFileExistsAndMatchesCheckedIn(self):
self.verifyCheckedInClangFormatFileExists()
foundClangFormatFiles = sets.Set()
for fileName in self.inputFiles:
dirName = os.path.dirname(os.path.abspath(fileName))
if not self.findClangFormatFileStartingFrom(dirName, fileName, foundClangFormatFiles):
sys.exit(1)
def findClangFormatFileStartingFrom(self, dirName, fileName, foundClangFormatFiles):
clangFormatFile = os.path.join(dirName, CodeFormatterClang.CLANG_FORMAT_FILE)
if os.path.exists(clangFormatFile):
if clangFormatFile not in foundClangFormatFiles:
foundClangFormatFiles.add(clangFormatFile)
if os.path.exists(self.checkedInClangFormatFile) and \
not filecmp.cmp(self.checkedInClangFormatFile, clangFormatFile):
cprint("[WARN] " + clangFormatFile + " does not match " + self.checkedInClangFormatFile, "yellow")
self.confirmWithUserClangFormatFileCantBeVerified()
else:
print("[OK] Found " + CodeFormatterClang.CLANG_FORMAT_FILE +
" file (used by the formatter) " + clangFormatFile)
return True
else:
dirNameOneLevelUp = os.path.dirname(dirName)
if dirNameOneLevelUp == dirName:
# dirName was already root folder -> clang-format file not found
cprint("[ERROR] Not found " + CodeFormatterClang.CLANG_FORMAT_FILE + " for " +
fileName + " in same directory or in any parent directory", "red")
return False
else:
return self.findClangFormatFileStartingFrom(dirNameOneLevelUp, fileName, foundClangFormatFiles)
class CodeFormatterAutopep(CodeFormatter):
def __init__(self):
CodeFormatter.__init__(self,
command="autopep8",
expectedVersion="",
formatCommandArguments=["--in-place", "--max-line-length=119"],
verifyCommandArguments=["--diff", "--max-line-length=119"],
verifyOutputIsDiff=True,
fileEndings=["py"],
fileDescription="python",
installCommand="sudo apt-get install python-pep8 python-autopep8")
class CodeFormat:
def __init__(self):
self.failure = False
self.codeFormatterInstances = []
return
def parseCommandLine(self):
parser = argparse.ArgumentParser(
description="Helper script for code formatting.")
parser.add_argument("input", nargs="+",
help="files or directories to process")
parser.add_argument("-v", "--verify", action="store_true",
help="do not change file, but only verify the format is correct")
parser.add_argument("-d", "--diff", action="store_true",
help="show diff, implies verify mode")
parser.add_argument("-e", "--exclude", nargs="+", metavar="exclude",
help="exclude files or directories containing words from the exclude list in their names")
parser.add_argument("-y", "--yes", action="store_true",
help="do not ask for confirmation before formatting more than one file")
parser.add_argument("--version", action="version", version="%(prog)s " + SCRIPT_VERSION)
self.args = parser.parse_args()
if self.args.diff:
self.args.verify = True
def addCodeFormatter(self, codeFormatterInstance):
self.codeFormatterInstances.append(codeFormatterInstance)
def scanForInputFiles(self):
for formatterInstance in self.codeFormatterInstances:
filePattern = re.compile("^[^.].*\.(" + "|".join(formatterInstance.fileEndings) + ")$")
formatterInstance.inputFiles = []
for fileOrDirectory in self.args.input:
if os.path.exists(fileOrDirectory):
formatterInstance.inputFiles.extend(self.scanFileOrDirectory(fileOrDirectory, filePattern))
else:
cprint("[WARN] Cannot find '" + fileOrDirectory + "'", "yellow")
def scanFileOrDirectory(self, fileOrDirectory, filePattern):
fileList = []
if os.path.isdir(fileOrDirectory):
for root, directories, fileNames in os.walk(fileOrDirectory):
directories[:] = self.filterDirectories(root, directories)
for filename in filter(lambda name: filePattern.match(name), fileNames):
fullFilename = os.path.join(root, filename)
if self.isFileNotExcluded(fullFilename):
fileList.append(fullFilename)
else:
if self.isFileNotExcluded(fileOrDirectory) and (filePattern.match(os.path.basename(fileOrDirectory)) is not None):
fileList.append(fileOrDirectory)
return fileList
def filterDirectories(self, root, directories):
# Exclude hidden directories and all directories that have a CODE_FORMAT_IGNORE_FILE
directories[:] = [directory for directory in directories if
not directory.startswith(".") and
not os.path.exists(os.path.join(root, directory, CodeFormatterClang.CODE_FORMAT_IGNORE_FILE))]
return directories
def isFileNotExcluded(self, fileName):
if self.args.exclude is not None:
for excluded in self.args.exclude:
if excluded in fileName:
return False
if os.path.islink(fileName):
return False
return True
def confirmWithUserFileIsOutsideGit(self, fileName):
cprint("[WARN] File is not in a Git repo: " + fileName, "yellow")
answer = raw_input("Are you sure to code format it anyway? (y/Q)")
if answer != "y":
sys.exit(1)
def confirmWithUserFileIsUntracked(self, fileName):
cprint("[WARN] File is untracked in Git: " + fileName, "yellow")
answer = raw_input("Are you sure to code format it anyway? (y/Q)")
if answer != "y":
sys.exit(1)
def confirmWithUserGitRepoIsNotClean(self, gitRepo):
cprint("[WARN] Git repo is not clean: " + gitRepo, "yellow")
answer = raw_input("Are you sure to code format files in it anyway? (y/Q)")
if answer != "y":
sys.exit(1)
def checkInputFilesAreInCleanGitReposAndAreTracked(self):
if self.args.verify or self.args.yes:
return
gitRepos = sets.Set()
for formatterInstance in self.codeFormatterInstances:
for fileName in formatterInstance.inputFiles:
gitRepo = self.getGitRepoForFile(fileName)
if gitRepo is None:
self.confirmWithUserFileIsOutsideGit(fileName)
else:
self.gitUpdateIndexRefresh(gitRepo)
if not self.isTrackedFile(fileName):
self.confirmWithUserFileIsUntracked(fileName)
elif gitRepo not in gitRepos:
gitRepos.add(gitRepo)
if not self.isCleanGitRepo(gitRepo):
self.confirmWithUserGitRepoIsNotClean(gitRepo)
def getGitRepoForFile(self, fileName):
if not self.isInsideGitRepo(fileName):
return None
try:
gitProcess = subprocess.Popen(["git", "rev-parse", "--show-toplevel"],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
cwd=os.path.dirname(fileName))
gitOutput, _ = gitProcess.communicate()
if gitProcess.returncode == 0:
return gitOutput.rstrip('\r\n')
except OSError:
cprint("[ERROR] Failed to run 'git rev-parse --show-toplevel' for " + fileName, "red")
return None
def isInsideGitRepo(self, fileName):
try:
gitProcess = subprocess.Popen(["git", "rev-parse", "--is-inside-work-tree"],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
cwd=os.path.dirname(fileName))
gitOutput, _ = gitProcess.communicate()
if gitProcess.returncode == 0:
return gitOutput.rstrip('\r\n') == "true"
except OSError:
cprint("[ERROR] Failed to run 'git rev-parse --is-inside-work-tree' for " + fileName, "red")
return False
def isTrackedFile(self, fileName):
try:
gitProcess = subprocess.Popen(["git", "ls-files", "--error-unmatch", "--", os.path.basename(fileName)],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
cwd=os.path.dirname(fileName))
_, _ = gitProcess.communicate()
if gitProcess.returncode == 0:
return True
except OSError:
cprint("[ERROR] Failed to run 'git ls-files --error-unmatch' for " + fileName, "red")
return False
def isCleanGitRepo(self, gitRepo):
try:
gitProcess = subprocess.Popen(["git", "diff-index", "--quiet", "HEAD", "--"],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
cwd=gitRepo)
_, _ = gitProcess.communicate()
if gitProcess.returncode == 0:
return True
except OSError:
cprint("[ERROR] Failed to run 'git diff-index --quiet HEAD --' for " + gitRepo, "red")
return False
def gitUpdateIndexRefresh(self, gitRepo):
try:
gitProcess = subprocess.Popen(["git", "update-index", "-q", "--ignore-submodules", "--refresh"],
stdin=subprocess.PIPE,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
cwd=gitRepo)
_, _ = gitProcess.communicate()
if gitProcess.returncode == 0:
return True
except OSError:
cprint("[ERROR] Failed to run 'git update-index -q --ignore-submodules --refresh' for " + gitRepo, "red")
return False
def verifyFormatterVersion(self):
for formatterInstance in self.codeFormatterInstances:
if len(formatterInstance.inputFiles) > 0:
formatterInstance.verifyFormatterVersion()
def printMode(self):
if self.args.verify:
cprint("VERIFY MODE", attrs=["bold"])
else:
cprint("FORMAT MODE", attrs=["bold"])
def processFiles(self):
for formatterInstance in self.codeFormatterInstances:
for fileName in formatterInstance.inputFiles:
if self.args.verify:
self.failure |= formatterInstance.verifyFile(fileName, self.args.diff)
else:
self.failure |= formatterInstance.formatFile(fileName)
def numberOfInputFiles(self):
count = 0
for formatterInstance in self.codeFormatterInstances:
count += len(formatterInstance.inputFiles)
return count
def confirmWithUser(self):
if self.numberOfInputFiles() == 0:
cprint("[WARN] No input files (or file endings unknown)", "yellow")
elif (not self.args.verify) and (not self.args.yes) and self.numberOfInputFiles() > 1:
for formatterInstance in self.codeFormatterInstances:
formatterInstance.printInputFiles()
answer = raw_input("Are you sure to code format " + str(self.numberOfInputFiles()) + " files? (y/N)")
if answer != "y":
sys.exit(1)
def main():
codeFormat = CodeFormat()
codeFormat.parseCommandLine()
codeFormat.printMode()
codeFormat.addCodeFormatter(CodeFormatterClang())
codeFormat.addCodeFormatter(CodeFormatterAutopep())
codeFormat.scanForInputFiles()
codeFormat.verifyFormatterVersion()
codeFormat.confirmWithUser()
codeFormat.checkInputFilesAreInCleanGitReposAndAreTracked()
codeFormat.processFiles()
if codeFormat.failure:
cprint("FAILURE", "red")
sys.exit(1)
else:
cprint("SUCCESS", "green")
sys.exit(0)
if __name__ == "__main__":
main()