Skip to content

Commit

Permalink
Merge pull request #1430 from tier4/fix/refactor-code
Browse files Browse the repository at this point in the history
Code Optimization and Refactoring
  • Loading branch information
hakuturu583 authored Nov 6, 2024
2 parents 2ec8909 + 1de0e8b commit 866a553
Show file tree
Hide file tree
Showing 17 changed files with 24 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class CatmullRomSpline : public CatmullRomSplineInterface
auto getPolygon(const double width, const size_t num_points = 30, const double z_offset = 0)
-> std::vector<geometry_msgs::msg::Point>;
const std::vector<geometry_msgs::msg::Point> control_points;
virtual ~CatmullRomSpline() = default;

private:
auto getRightBounds(const double width, const size_t num_points = 30, const double z_offset = 0)
Expand Down
2 changes: 0 additions & 2 deletions common/math/geometry/test/src/quaternion/test_quaternion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@
#include "../expect_eq_macros.hpp"
#include "../test_utils.hpp"

constexpr double EPS = 1e-6;

/**
* @note Test result correctness with a basic example.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@

#include "../expect_eq_macros.hpp"

constexpr double EPS = 1e-6;

/**
* @brief Custom Vector3 struct using T type with multiplication and division operators
*/
Expand Down
2 changes: 0 additions & 2 deletions common/math/geometry/test/src/vector3/test_truncate_msg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
#include "../expect_eq_macros.hpp"
#include "../test_utils.hpp"

constexpr double EPS = 1e-6;

TEST(Vector3, truncate_msgVectorBelowMax)
{
geometry_msgs::msg::Vector3 vec0 = makeVector(4.0, 4.0, 4.0);
Expand Down
2 changes: 1 addition & 1 deletion common/status_monitor/src/status_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ StatusMonitor::~StatusMonitor()
{
auto lock = std::scoped_lock<std::mutex>(mutex);

auto mark_as_exited = [this]() {
auto mark_as_exited = []() {
if (auto iter = statuses.find(std::this_thread::get_id()); iter != std::end(statuses)) {
std::get<1>(*iter).exited = true;
}
Expand Down
2 changes: 1 addition & 1 deletion external/concealer/include/concealer/autoware_universe.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ class AutowareUniverse : public Autoware
autoware_auto_control_msgs::msg::AckermannControlCommand,
autoware_auto_vehicle_msgs::msg::GearCommand> override;

auto getRouteLanelets() const -> std::vector<std::int64_t>;
auto getRouteLanelets() const -> std::vector<std::int64_t> override;
};

} // namespace concealer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class FieldOperatorApplicationFor<AutowareUniverse>
: public FieldOperatorApplication,
public TransitionAssertion<FieldOperatorApplicationFor<AutowareUniverse>>
{
friend class TransitionAssertion<FieldOperatorApplicationFor<AutowareUniverse>>;
friend struct TransitionAssertion<FieldOperatorApplicationFor<AutowareUniverse>>;

// clang-format off
SubscriberWrapper<autoware_auto_control_msgs::msg::AckermannControlCommand> getAckermannControlCommand;
Expand Down Expand Up @@ -178,7 +178,6 @@ class FieldOperatorApplicationFor<AutowareUniverse>
getLocalizationState("/api/localization/initialization_state", rclcpp::QoS(1).transient_local(), *this),
#endif
getMrmState("/api/fail_safe/mrm_state", rclcpp::QoS(1), *this, [this](const auto & v) { receiveMrmState(v); }),
getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this),
getTrajectory("/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1), *this),
getTurnIndicatorsCommandImpl("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this),
requestClearRoute("/api/routing/clear_route", *this),
Expand All @@ -188,7 +187,8 @@ class FieldOperatorApplicationFor<AutowareUniverse>
// NOTE: /api/routing/set_route_points takes a long time to return. But the specified duration is not decided by any technical reasons.
requestSetRoutePoints("/api/routing/set_route_points", *this, std::chrono::seconds(10)),
requestSetRtcAutoMode("/api/external/set/rtc_auto_mode", *this),
requestSetVelocityLimit("/api/autoware/set/velocity_limit", *this)
requestSetVelocityLimit("/api/autoware/set/velocity_limit", *this),
getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this)
// clang-format on
{
}
Expand Down
2 changes: 1 addition & 1 deletion external/concealer/src/autoware_universe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ auto AutowareUniverse::updateLocalization() -> void

auto AutowareUniverse::updateVehicleState() -> void
{
setControlModeReport([this]() {
setControlModeReport([]() {
autoware_auto_vehicle_msgs::msg::ControlModeReport message;
message.mode = autoware_auto_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS;
return message;
Expand Down
4 changes: 2 additions & 2 deletions external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ auto FieldOperatorApplication::shutdownAutoware() -> void
}
}();

const auto timeout = [this]() {
auto sigterm_timeout = [this](auto value) {
const auto timeout = []() {
auto sigterm_timeout = [](auto value) {
auto node = rclcpp::Node("get_parameter_sigterm_timeout", "simulation");
node.declare_parameter<int>("sigterm_timeout", value);
node.get_parameter<int>("sigterm_timeout", value);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ auto FieldOperatorApplicationFor<AutowareUniverse>::sendCooperateCommand(
* to avoid sending the same cooperate command when sending multiple commands between updates of cooperate statuses.
*/
static std::vector<tier4_rtc_msgs::msg::CooperateStatus> used_cooperate_statuses;
auto is_used_cooperate_status = [this](const auto & cooperate_status) {
auto is_used_cooperate_status = [](const auto & cooperate_status) {
return std::find_if(
used_cooperate_statuses.begin(), used_cooperate_statuses.end(),
[&cooperate_status](const auto & used_cooperate_status) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,9 @@ auto FollowWaypointController::roundTimeToFullStepsWithTolerance(
throw ControllerError(
"Value remaining_time_source (", remaining_time_source,
") is NaN or inf - it cannot be rounded.");
} else if (remaining_time_source >= std::numeric_limits<std::size_t>::max() * step_time) {
} else if (
remaining_time_source >=
static_cast<double>(std::numeric_limits<std::size_t>::max()) * step_time) {
throw ControllerError(
"Exceeded the range of the variable type <std::size_t> (", remaining_time_source, "/",
step_time, ") - the value is too large. Probably the distance to the waypoint is extremely",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

namespace traffic_simulator
{
namespace entity_status
inline namespace entity_status
{

CanonicalizedEntityStatus::CanonicalizedEntityStatus(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

namespace traffic_simulator
{
namespace lanelet_pose
inline namespace lanelet_pose
{
CanonicalizedLaneletPose::CanonicalizedLaneletPose(
const LaneletPose & maybe_non_canonicalized_lanelet_pose,
Expand Down
14 changes: 7 additions & 7 deletions simulation/traffic_simulator/src/entity/entity_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ EntityBase::EntityBase(
traveled_distance_ += std::abs(getCurrentTwist().linear.x) * step_time_;
return false;
},
[this]() {}, job::Type::TRAVELED_DISTANCE, true, job::Event::POST_UPDATE);
[]() {}, job::Type::TRAVELED_DISTANCE, true, job::Event::POST_UPDATE);

if (name != static_cast<EntityStatus>(entity_status).name) {
THROW_SIMULATION_ERROR(
Expand All @@ -62,7 +62,7 @@ EntityBase::EntityBase(
}
return false;
},
[this]() {}, job::Type::STAND_STILL_DURATION, true, job::Event::POST_UPDATE);
[]() {}, job::Type::STAND_STILL_DURATION, true, job::Event::POST_UPDATE);
}

void EntityBase::appendDebugMarker(visualization_msgs::msg::MarkerArray &) {}
Expand Down Expand Up @@ -440,7 +440,7 @@ void EntityBase::requestSpeedChange(double target_speed, bool continuous)
/**
* @brief Cancel speed change request.
*/
[this]() {}, job::Type::LINEAR_VELOCITY, true, job::Event::POST_UPDATE);
[]() {}, job::Type::LINEAR_VELOCITY, true, job::Event::POST_UPDATE);
} else {
target_speed_ = target_speed;
job_list_.append(
Expand Down Expand Up @@ -480,7 +480,7 @@ void EntityBase::requestSpeedChange(
target_speed_ = target_speed.getAbsoluteValue(getCanonicalizedStatus(), other_status_);
return false;
},
[this]() {}, job::Type::LINEAR_VELOCITY, true, job::Event::POST_UPDATE);
[]() {}, job::Type::LINEAR_VELOCITY, true, job::Event::POST_UPDATE);
} else {
job_list_.append(
/**
Expand Down Expand Up @@ -608,7 +608,7 @@ void EntityBase::activateOutOfRangeJob(
* @brief Checking if the values of velocity, acceleration and jerk are within the acceptable
* range
*/
[this, tolerance, max_velocity, min_velocity, min_acceleration, max_acceleration, min_jerk,
[this, max_velocity, min_velocity, min_acceleration, max_acceleration, min_jerk,
max_jerk](double) {
const auto velocity = getCurrentTwist().linear.x;
const auto accel = getCurrentAccel().linear.x;
Expand All @@ -633,7 +633,7 @@ void EntityBase::activateOutOfRangeJob(
/**
* @brief This job is always ACTIVE
*/
[this]() {}, job::Type::OUT_OF_RANGE, true, job::Event::POST_UPDATE);
[]() {}, job::Type::OUT_OF_RANGE, true, job::Event::POST_UPDATE);
}

void EntityBase::stopAtCurrentPosition()
Expand Down Expand Up @@ -768,7 +768,7 @@ auto EntityBase::requestSynchronize(
target_speed_ = entity_velocity_to_synchronize();
return false;
},
[this]() {}, job::Type::LINEAR_ACCELERATION, true, job::Event::POST_UPDATE);
[]() {}, job::Type::LINEAR_ACCELERATION, true, job::Event::POST_UPDATE);
return false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -535,7 +535,6 @@ auto HdMapUtils::matchToLane(
const bool include_crosswalk, const double matching_distance, const double reduction_ratio) const
-> std::optional<lanelet::Id>
{
std::optional<lanelet::Id> id;
lanelet::matching::Object2d obj;
obj.pose.translation() = toPoint2d(pose.position);
obj.pose.linear() =
Expand Down
2 changes: 1 addition & 1 deletion simulation/traffic_simulator/src/utils/distance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

namespace traffic_simulator
{
namespace distance
inline namespace distance
{
auto lateralDistance(
const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
Expand Down
2 changes: 1 addition & 1 deletion simulation/traffic_simulator/src/utils/pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

namespace traffic_simulator
{
namespace pose
inline namespace pose
{
auto quietNaNPose() -> geometry_msgs::msg::Pose
{
Expand Down

0 comments on commit 866a553

Please sign in to comment.