Skip to content

Commit

Permalink
resolved changes requested in my pr
Browse files Browse the repository at this point in the history
  • Loading branch information
shourikb committed Oct 30, 2024
1 parent 19504d8 commit 8418efe
Show file tree
Hide file tree
Showing 4 changed files with 55 additions and 14 deletions.
53 changes: 53 additions & 0 deletions rj_geometry/include/rj_geometry/stadium_shape.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,28 @@ class StadiumShape : public Shape {
init(c1, c2, r);
}

StadiumShape(const StadiumShape& other) {
for (const auto& shape : other.subshapes_) {
std::shared_ptr<Shape> itr_shape = std::shared_ptr<Shape>(shape->clone());
subshapes_.push_back(itr_shape);
}
drawshapes_ = other.drawshapes_;
}

[[nodiscard]] Shape* clone() const override;

[[nodiscard]] bool contains_point(Point pt) const override;
[[nodiscard]] bool near_point(Point pt, float threshold) const override;

using const_iterator = std::vector<std::shared_ptr<Shape>>::const_iterator;
using iterator = std::vector<std::shared_ptr<Shape>>::iterator;

[[nodiscard]] const_iterator begin() const { return subshapes_.begin(); }
[[nodiscard]] const_iterator end() const { return subshapes_.end(); }

iterator begin() { return subshapes_.begin(); }
iterator end() { return subshapes_.end(); }

[[nodiscard]] const std::vector<std::shared_ptr<Shape>>& subshapes() const {
return subshapes_;
}
Expand All @@ -37,6 +54,42 @@ class StadiumShape : public Shape {
return drawshapes_;
}

std::shared_ptr<Shape> operator[](unsigned int index) {
return subshapes_[index];
}

std::shared_ptr<const Shape> operator[](unsigned int index) const {
return subshapes_[index];
}

template <typename T>
[[nodiscard]] bool hit(const T& obj) const {
for (const auto& it : *this) {

Check warning on line 67 in rj_geometry/include/rj_geometry/stadium_shape.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

replace loop by 'std::any_of()'
if (it->hit(obj)) {
return true;
}
}

return false;
}

[[nodiscard]] bool hit(Point pt) const override { return hit<Point>(pt); }

[[nodiscard]] bool hit(const Segment& seg) const override {
return hit<Segment>(seg);
}

std::string to_string() override {
std::stringstream str;
str << "StadiumShape<";
for (auto& subshape : subshapes_) {
str << subshape->to_string() << ", ";
}
str << ">";

return str.str();
}

protected:
void init(Point c1, Point c2, float r);

Expand Down
6 changes: 0 additions & 6 deletions soccer/src/soccer/debug_drawer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,6 @@ void DebugDrawer::draw_circle(rj_geometry::Point center, float radius, const QCo
dbg->set_color(color(qc));
}

// void DebugDrawer::draw_stadium(rj_geometry::StadiumShape& stadium, const QColor& qc, const QString& layer) {
// this->draw_circle(stadium.drawshapes()[0], qc, layer);
// this->draw_polygon(stadium.drawshapes()[1], qc, layer);
// this->draw_circle(stadium.drawshapes()[2], qc, layer);
// }

void DebugDrawer::draw_arc(const rj_geometry::Arc& arc, const QColor& qc, const QString& layer) {
Packet::DebugArc* dbg = log_frame_.add_debug_arcs();
dbg->set_layer(find_debug_layer(layer));
Expand Down
5 changes: 0 additions & 5 deletions soccer/src/soccer/debug_drawer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#include <rj_geometry/arc.hpp>
#include <rj_geometry/composite_shape.hpp>
#include <rj_geometry/stadium_shape.hpp>
#include <rj_geometry/point.hpp>
#include <rj_geometry/polygon.hpp>
#include <rj_geometry/segment.hpp>
Expand Down Expand Up @@ -79,10 +78,6 @@ class DebugDrawer {
const QColor& qw = Qt::black,
const QString& layer = QString());

// void draw_stadium(rj_geometry::StadiumShape& stadium,
// const QColor& qc = Qt::black,
// const QString& layer = QString());

/**
* Fill the given log frame with the current debug drawing information,
* and reset our current debug drawing data for the next cycle.
Expand Down
5 changes: 2 additions & 3 deletions soccer/src/soccer/planning/planner/plan_request.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,10 +84,9 @@ void fill_obstacles(const PlanRequest& in, rj_geometry::ShapeSet* out_static,
rj_geometry::Point bp_point = maybe_bp_point.value();
rj_geometry::StadiumShape stadium = rj_geometry::StadiumShape{in.world_state->ball.position, bp_point, ball_obs.radius()};

Check warning on line 85 in soccer/src/soccer/planning/planner/plan_request.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

'ball_obs' used after it was moved

// for some reason adding the shared pointer below to our static obstacles breaks it, so we add the shape set it has instead.
// std::shared_ptr<rj_geometry::Shape> track_obs_ptr = std::make_shared<rj_geometry::Shape>(stadium);
std::shared_ptr<rj_geometry::StadiumShape> track_obs_ptr = std::make_shared<rj_geometry::StadiumShape>(stadium);

out_static->add(stadium.drawshapes());
out_static->add(track_obs_ptr);

if (in.debug_drawer != nullptr) {
QColor draw_color = Qt::red;
Expand Down

0 comments on commit 8418efe

Please sign in to comment.