Skip to content

Commit

Permalink
pass a reference
Browse files Browse the repository at this point in the history
  • Loading branch information
sanatd33 committed Nov 11, 2024
1 parent 2fe51e9 commit 874a552
Show file tree
Hide file tree
Showing 7 changed files with 22 additions and 22 deletions.
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/global_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ GlobalState::GlobalState(rclcpp::Node* node) {
auto lock = std::lock_guard(last_world_state_mutex_);
return &last_world_state_;
}
[[nodiscard]] FieldDimensions GlobalState::field_dimensions() const {
[[nodiscard]] const FieldDimensions* GlobalState::field_dimensions() const {
auto lock = std::lock_guard(last_field_dimensions_mutex_);
return last_field_dimensions_;
return &last_field_dimensions_;
}

rj_geometry::ShapeSet GlobalState::create_defense_area_obstacles() {
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/global_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ class GlobalState {
[[nodiscard]] rj_geometry::ShapeSet global_obstacles() const;
[[nodiscard]] rj_geometry::ShapeSet def_area_obstacles() const;
[[nodiscard]] const WorldState* world_state() const;
[[nodiscard]] FieldDimensions field_dimensions() const;
[[nodiscard]] const FieldDimensions* field_dimensions() const;

private:
rclcpp::Subscription<rj_msgs::msg::PlayState>::SharedPtr play_state_sub_;
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/planning/planner/plan_request.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ struct PlanRequest {
RobotConstraints constraints, rj_geometry::ShapeSet field_obstacles,
rj_geometry::ShapeSet virtual_obstacles, TrajectoryCollection* planned_trajectories,
unsigned shell_id, const WorldState* world_state, PlayState play_state,
FieldDimensions field_dimensions, int8_t priority = 0,
const FieldDimensions* field_dimensions, int8_t priority = 0,
rj_drawing::RosDebugDrawer* debug_drawer = nullptr, bool ball_sense = false,
float min_dist_from_ball = 0, float dribbler_speed = 0)
: start(start),
Expand Down Expand Up @@ -107,7 +107,7 @@ struct PlanRequest {
/**
* the Field Dimensions
*/
FieldDimensions field_dimensions;
const FieldDimensions* field_dimensions;

/**
* Allows debug drawing in the world. If this is nullptr, no debug drawing
Expand Down
8 changes: 4 additions & 4 deletions soccer/src/soccer/planning/primitives/create_path.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ Trajectory intermediate(const LinearMotionInstant& start, const LinearMotionInst
const MotionConstraints& motion_constraints, RJ::Time start_time,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles,
const FieldDimensions field_dimensions, unsigned int robot_id) {
const FieldDimensions* field_dimensions, unsigned int robot_id) {
// if already on goal, no need to move
if (start.position.dist_to(goal.position) < 1e-6) {
return Trajectory{{RobotInstant{Pose(start.position, 0), Twist(), start_time}}};
Expand Down Expand Up @@ -111,13 +111,13 @@ Trajectory intermediate(const LinearMotionInstant& start, const LinearMotionInst
rj_geometry::Point intermediate =
(final_inter - start.position).normalized(t) + start.position;

auto offset = intermediate - field_dimensions.center_point();
auto offset = intermediate - field_dimensions->center_point();

// Ignore out-of-bounds intermediate points
// The offset 0.2m is chosen because the sim prevents you from moving
// more than 0.2m away from the border lines
if (abs(offset.x()) > field_dimensions.width() / 2 + 0.2 ||
abs(offset.y()) > field_dimensions.length() / 2 + 0.2) {
if (abs(offset.x()) > field_dimensions->width() / 2 + 0.2 ||
abs(offset.y()) > field_dimensions->length() / 2 + 0.2) {
continue;
}

Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/primitives/create_path.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ Trajectory intermediate(const LinearMotionInstant& start, const LinearMotionInst
const MotionConstraints& motion_constraints, RJ::Time start_time,
const rj_geometry::ShapeSet& static_obstacles,
const std::vector<DynamicObstacle>& dynamic_obstacles,
const FieldDimensions field_dimensions, unsigned int robot_id);
const FieldDimensions* field_dimensions, unsigned int robot_id);

std::vector<rj_geometry::Point> get_intermediates(const LinearMotionInstant& start,
const LinearMotionInstant& goal,
Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/planning/primitives/replanner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ class Replanner {
LinearMotionInstant goal;
const rj_geometry::ShapeSet& static_obstacles;
const std::vector<DynamicObstacle>& dynamic_obstacles;
const FieldDimensions field_dimensions;
const FieldDimensions* field_dimensions;
RobotConstraints constraints;
const AngleFunction& angle_function;
unsigned int robot_id;
Expand Down
22 changes: 11 additions & 11 deletions soccer/src/soccer/planning/tests/planner_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ TEST(Planning, path_target_random) {

WorldState world_state;
PathTargetPathPlanner planner;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;

int failure_count = 0;
for (int i = 0; i < 1000; i++) {
Expand Down Expand Up @@ -90,7 +90,7 @@ TEST(Planning, path_target_random) {

TEST(Planning, collect_basic) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{1, 1};
world_state.ball.velocity = Point{0, 0};
world_state.ball.timestamp = RJ::now();
Expand All @@ -114,7 +114,7 @@ TEST(Planning, collect_basic) {

TEST(Planning, collect_obstructed) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{1, 1};
world_state.ball.velocity = Point{0, 0};
world_state.ball.timestamp = RJ::now();
Expand All @@ -140,7 +140,7 @@ TEST(Planning, collect_obstructed) {

TEST(Planning, collect_pointless_obs) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{1, 1};
world_state.ball.velocity = Point{0, 0};
world_state.ball.timestamp = RJ::now();
Expand Down Expand Up @@ -169,7 +169,7 @@ TEST(Planning, collect_pointless_obs) {

TEST(Planning, collect_moving_ball_quick) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{-1, 1};
world_state.ball.velocity = Point{-0.03, 0.3};
world_state.ball.timestamp = RJ::now();
Expand All @@ -195,7 +195,7 @@ TEST(Planning, collect_moving_ball_quick) {

TEST(Planning, collect_moving_ball_slow) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{-1, 1};
world_state.ball.velocity = Point{0, 0.1};
world_state.ball.timestamp = RJ::now();
Expand All @@ -221,7 +221,7 @@ TEST(Planning, collect_moving_ball_slow) {

TEST(Planning, collect_moving_ball_slow_2) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{-1, 1};
world_state.ball.velocity = Point{0.01, 0.05};
world_state.ball.timestamp = RJ::now();
Expand All @@ -248,7 +248,7 @@ TEST(Planning, collect_moving_ball_slow_2) {
TEST(Planning, collect_random) {
std::mt19937 gen(1337);
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;

int failure_count = 0;

Expand Down Expand Up @@ -295,7 +295,7 @@ TEST(Planning, collect_random) {

TEST(Planning, settle_basic) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
world_state.ball.position = Point{1, 1};
world_state.ball.velocity = Point{-1, -1.5};
world_state.ball.timestamp = RJ::now();
Expand All @@ -321,7 +321,7 @@ TEST(Planning, settle_basic) {

TEST(Planning, settle_pointless_obs) {
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;
// Use some initial velocity, settle doesn't always work for non-moving
// balls
world_state.ball.position = Point{1, 3};
Expand Down Expand Up @@ -351,7 +351,7 @@ TEST(Planning, settle_pointless_obs) {
TEST(Planning, settle_random) {
std::mt19937 gen(1337);
WorldState world_state;
FieldDimensions field_dimensions = FieldDimensions::current_dimensions;
FieldDimensions* field_dimensions = &FieldDimensions::current_dimensions;

int failure_count = 0;

Expand Down

0 comments on commit 874a552

Please sign in to comment.