Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix/sonor cloud issue 8 #1455

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
Open
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +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;
~CatmullRomSpline() override = default;

private:
auto getRightBounds(const double width, const size_t num_points = 30, const double z_offset = 0)
Expand Down
24 changes: 12 additions & 12 deletions common/math/geometry/src/spline/catmull_rom_spline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,8 +470,8 @@ auto CatmullRomSpline::getSquaredDistanceIn2D(
}
return line_segments_[0].getSquaredDistanceIn2D(point, s, true);
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getSquaredDistanceIn2D(point, index_and_s.second, true);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getSquaredDistanceIn2D(point, s_value, true);
}
}

Expand Down Expand Up @@ -508,8 +508,8 @@ auto CatmullRomSpline::getSquaredDistanceVector(
}
return line_segments_[0].getSquaredDistanceVector(point, s, true);
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getSquaredDistanceVector(point, index_and_s.second, true);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getSquaredDistanceVector(point, s_value, true);
}
}

Expand Down Expand Up @@ -542,8 +542,8 @@ auto CatmullRomSpline::getPoint(const double s) const -> geometry_msgs::msg::Poi
}
return line_segments_[0].getPoint(s, true);
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getPoint(index_and_s.second, true);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getPoint(s_value, true);
}
}

Expand Down Expand Up @@ -597,8 +597,8 @@ auto CatmullRomSpline::getNormalVector(const double s) const -> geometry_msgs::m
"This message is not originally intended to be displayed, if you see it, please "
"contact the developer of traffic_simulator.");
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getNormalVector(index_and_s.second, true);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getNormalVector(s_value, true);
}
}

Expand Down Expand Up @@ -634,8 +634,8 @@ auto CatmullRomSpline::getTangentVector(const double s) const -> geometry_msgs::
"This message is not originally intended to be displayed, if you see it, please "
"contact the developer of traffic_simulator.");
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getTangentVector(index_and_s.second, true);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getTangentVector(s_value, true);
}
}

Expand Down Expand Up @@ -665,8 +665,8 @@ auto CatmullRomSpline::getPose(const double s, const bool fill_pitch) const
}
return line_segments_[0].getPose(s, true, fill_pitch);
default:
const auto index_and_s = getCurveIndexAndS(s);
return curves_[index_and_s.first].getPose(index_and_s.second, true, fill_pitch);
const auto [index, s_value] = getCurveIndexAndS(s);
return curves_[index].getPose(s_value, true, fill_pitch);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
* but the initial value of 35.0 is set to ensure a default size that is likely suitable for most screens.
* The scaling factor adjusts this size to ensure readability across various resolutions.
*/
const float text_size = scale * 35.0;
const float text_size = scale * 35.0f;

/// @note Define initial value of left edge position of condition results panel
const int left = 0;
Expand All @@ -60,21 +60,21 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
* The purpose of this calculation is to position the top edge of the panel at an appropriate place on the screen,
* again scaling according to screen resolution to maintain a consistent look across different devices.
*/
const int top = static_cast<int>(std::round(450 * scale));
const auto top = static_cast<int>(std::round(450 * scale));

/**
* @note Define initial value of horizontal length of condition results panel.
* The reason 2000 is hard-coded here is because that number displayed most beautifully when we tested the operation on a 4K/non 4K display.
* Also, this number can be set via the rviz GUI.
*/
const int length = static_cast<int>(std::round(2000 * scale));
const auto length = static_cast<int>(std::round(2000 * scale));

/**
* @note Define initial value of width of condition results panel.
* The reason 2000 is hard-coded here is because that number displayed most beautifully when we tested the operation on a 4K/non 4K display.
* Also, this number can be set via the rviz GUI.
*/
const int width = static_cast<int>(std::round(2000 * scale));
const auto width = static_cast<int>(std::round(2000 * scale));

property_topic_name_ = std::make_unique<rviz_common::properties::StringProperty>(
"Topic", "/simulation/context", "The topic on which to publish simulation context.", this,
Expand All @@ -99,7 +99,7 @@ VisualizationConditionGroupsDisplay::VisualizationConditionGroupsDisplay()
"This property controls the scaling factor for the text size on the panel. Setting a higher "
"value results in larger text, making the displayed information easier to read.",
this, SLOT(updateVisualization()), this);
property_value_scale_->setMin(0.01);
property_value_scale_->setMin(0.01f);
}

VisualizationConditionGroupsDisplay::~VisualizationConditionGroupsDisplay()
Expand Down Expand Up @@ -171,10 +171,9 @@ void VisualizationConditionGroupsDisplay::processMessage(const Context::ConstSha

QPainter painter(&hud);
painter.setRenderHint(QPainter::Antialiasing, true);
// QColor text_color = property_text_color_->getColor();
QColor text_color(property_text_color_->getColor());
text_color.setAlpha(255);
painter.setPen(QPen(text_color, static_cast<int>(2), Qt::SolidLine));
painter.setPen(QPen(text_color, 2, Qt::SolidLine));
QFont font = painter.font();
font.setPixelSize(std::max(static_cast<int>(property_value_scale_->getFloat()), 1));
font.setBold(true);
Expand Down Expand Up @@ -262,7 +261,7 @@ void VisualizationConditionGroupsDisplay::processEvent(const YAML::Node & event_
std::string event_name;
try {
event_name = event_node["name"].as<std::string>();
} catch (const YAML::BadConversion & e) {
} catch (const YAML::BadConversion &) {
event_name = "";
}
if (event_name.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,13 @@ class PedestrianEntity : public EntityBase

void setTrafficLights(const std::shared_ptr<traffic_simulator::TrafficLightsBase> & ptr) override;

auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter;
auto getBehaviorParameter() const -> traffic_simulator_msgs::msg::BehaviorParameter override;

auto getMaxAcceleration() const -> double override;

auto getMaxDeceleration() const -> double override;

void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &);
void setBehaviorParameter(const traffic_simulator_msgs::msg::BehaviorParameter &) override;

void setVelocityLimit(double linear_velocity) override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,14 +74,14 @@ void VisualizationComponent::entityStatusCallback(
entity_name_lists.emplace_back(data.status.name);
}
std::vector<std::string> erase_names;
for (const auto & marker : markers_) {
auto itr = std::find(entity_name_lists.begin(), entity_name_lists.end(), marker.first);
for (const auto & [key, marker] : markers_) {
auto itr = std::find(entity_name_lists.begin(), entity_name_lists.end(), key);
if (itr == entity_name_lists.end()) {
auto delete_marker = generateDeleteMarker(marker.first);
auto delete_marker = generateDeleteMarker(key);
std::copy(
delete_marker.markers.begin(), delete_marker.markers.end(),
std::back_inserter(current_marker.markers));
erase_names.emplace_back(marker.first);
erase_names.emplace_back(key);
}
}
for (const auto & name : erase_names) {
Expand Down Expand Up @@ -336,7 +336,6 @@ const visualization_msgs::msg::MarkerArray VisualizationComponent::generateMarke
arrow.id = 2;
arrow.action = visualization_msgs::msg::Marker::ADD;

// constexpr double arrow_size = 0.3;
double arrow_size = 0.4 * status.bounding_box.dimensions.y;
constexpr double arrow_ratio = 1.0;
geometry_msgs::msg::Point pf, pl, pr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,19 +51,19 @@ class LaneletUtils

double computeDistance(
const traffic_simulator_msgs::msg::LaneletPose & p1,
const traffic_simulator_msgs::msg::LaneletPose & p2);
const traffic_simulator_msgs::msg::LaneletPose & p2) const;
std::optional<traffic_simulator_msgs::msg::LaneletPose> getOppositeLaneLet(
const traffic_simulator_msgs::msg::LaneletPose & pose);
std::vector<LaneletPart> getLanesWithinDistance(
const traffic_simulator_msgs::msg::LaneletPose & pose, double min_distance,
double max_distance);

std::vector<int64_t> getLaneletIds();
std::vector<int64_t> getLaneletIds() const;
geometry_msgs::msg::PoseStamped toMapPose(
const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose, const bool fill_pitch);
std::vector<int64_t> getRoute(int64_t from_lanelet_id, int64_t to_lanelet_id);
double getLaneletLength(int64_t lanelet_id);
bool isInLanelet(int64_t lanelet_id, double s);
const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose, const bool fill_pitch) const;
std::vector<int64_t> getRoute(int64_t from_lanelet_id, int64_t to_lanelet_id) const;
double getLaneletLength(int64_t lanelet_id) const;
bool isInLanelet(int64_t lanelet_id, double s) const;

private:
lanelet::LaneletMapPtr lanelet_map_ptr_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ class EgoCollisionMetric
{
timeoutCollisions(current_time);

auto npc_insertion_data = npc_last_collision_type_map_.emplace(npc_name, current_time);
if (npc_insertion_data.second) {
auto [_, was_inserted] = npc_last_collision_type_map_.emplace(npc_name, current_time);
if (was_inserted) {
return true;
}
npc_last_collision_type_map_[npc_name] = current_time;
Expand Down
18 changes: 10 additions & 8 deletions test_runner/random_test_runner/src/lanelet_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,27 +47,30 @@ LaneletUtils::LaneletUtils(const boost::filesystem::path & filename)
std::make_shared<hdmap_utils::HdMapUtils>(filename, geographic_msgs::msg::GeoPoint());
}

std::vector<int64_t> LaneletUtils::getLaneletIds() { return hdmap_utils_ptr_->getLaneletIds(); }
std::vector<int64_t> LaneletUtils::getLaneletIds() const
{
return hdmap_utils_ptr_->getLaneletIds();
}

geometry_msgs::msg::PoseStamped LaneletUtils::toMapPose(
const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose, const bool fill_pitch)
const traffic_simulator_msgs::msg::LaneletPose & lanelet_pose, const bool fill_pitch) const
{
return hdmap_utils_ptr_->toMapPose(lanelet_pose, fill_pitch);
}

std::vector<int64_t> LaneletUtils::getRoute(int64_t from_lanelet_id, int64_t to_lanelet_id)
std::vector<int64_t> LaneletUtils::getRoute(int64_t from_lanelet_id, int64_t to_lanelet_id) const
{
return hdmap_utils_ptr_->getRoute(from_lanelet_id, to_lanelet_id);
}

double LaneletUtils::getLaneletLength(int64_t lanelet_id)
double LaneletUtils::getLaneletLength(int64_t lanelet_id) const
{
return hdmap_utils_ptr_->getLaneletLength(lanelet_id);
}

double LaneletUtils::computeDistance(
const traffic_simulator_msgs::msg::LaneletPose & p1,
const traffic_simulator_msgs::msg::LaneletPose & p2)
const traffic_simulator_msgs::msg::LaneletPose & p2) const
{
auto p1_g = hdmap_utils_ptr_->toMapPose(p1).pose.position;
auto p2_g = hdmap_utils_ptr_->toMapPose(p2).pose.position;
Expand All @@ -78,7 +81,7 @@ double LaneletUtils::computeDistance(
return std::sqrt(d.x * d.x + d.y * d.y + d.z * d.z);
}

bool LaneletUtils::isInLanelet(int64_t lanelet_id, double s)
bool LaneletUtils::isInLanelet(int64_t lanelet_id, double s) const
{
return hdmap_utils_ptr_->isInLanelet(lanelet_id, s);
}
Expand Down Expand Up @@ -278,8 +281,7 @@ std::vector<LaneletPart> LaneletUtils::getLanesWithinDistance(
}

std::vector<LaneletPart> ret;
for (const auto & lanelet_part_key_value : lanelets_within_distance) {
const auto & lanelet_part = lanelet_part_key_value.second;
for (const auto & [_, lanelet_part] : lanelets_within_distance) {
ret.emplace_back(
LaneletPart{lanelet_part.lanelet.id(), lanelet_part.start_s, lanelet_part.end_s});
}
Expand Down
Loading