Skip to content

Commit

Permalink
Fix formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
griswaldbrooks committed Sep 8, 2023
1 parent 9037b82 commit 9457301
Show file tree
Hide file tree
Showing 6 changed files with 444 additions and 408 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ jobs:
restore-keys: |
ccache-ros-${{ matrix.ros_distro }}-${{ github.sha }}
ccache-ros-${{ matrix.ros_distro }}
- uses: ros-tooling/action-ros-ci@v0.2
- uses: ros-tooling/action-ros-ci@v0.3
with:
target-ros2-distro: ${{ matrix.ros_distro }}
colcon-defaults: |
Expand Down
2 changes: 1 addition & 1 deletion example_srvs/srv/GetPath.srv
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,4 @@ std_msgs/UInt8MultiArray start
std_msgs/UInt8MultiArray goal
---
std_msgs/Bool success
std_msgs/UInt8MultiArray path
std_msgs/UInt8MultiArray path
2 changes: 1 addition & 1 deletion example_srvs/srv/SetMap.srv
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
std_msgs/UInt8MultiArray map
---
std_msgs/Bool success
std_msgs/Bool success
2 changes: 1 addition & 1 deletion functional_programming_tests/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -52,4 +52,4 @@ public:
// ... more code
```

Writing all this extra code can be time consuming and lead to bugs in testing. In `with_functional_programming.cpp`, the `generate_global_path` method is now a free function, and the `costmap_callback` and `get_costmap` functions aren't needed anymore. This leads to less boilerplate code required to test `generate_global_path`.
Writing all this extra code can be time consuming and lead to bugs in testing. In `with_functional_programming.cpp`, the `generate_global_path` method is now a free function, and the `costmap_callback` and `get_costmap` functions aren't needed anymore. This leads to less boilerplate code required to test `generate_global_path`.
189 changes: 95 additions & 94 deletions functional_programming_tests/test/with_functional_programming.cpp
Original file line number Diff line number Diff line change
@@ -1,81 +1,83 @@
#include <gtest/gtest.h>

#include <iostream>
#include <vector>
#include <cmath>
#include <iostream>
#include <optional>
#include <vector>

#include <gtest/gtest.h>

// production_code.h/cc
// X, Y position
struct Position {
size_t x;
size_t y;
size_t x;
size_t y;
};

template<typename T>
class Map
{
public:
Map(std::vector<std::vector<T>> data): data_{data} {};
T at(Position const& pos) const {
return data_.at(pos.y).at(pos.x);
}
private:
std::vector<std::vector<T>> data_;
template <typename T>
class Map {
public:
Map(std::vector<std::vector<T>> data) : data_{data} {};
T at(Position const& pos) const { return data_.at(pos.y).at(pos.x); }

private:
std::vector<std::vector<T>> data_;
};

using Path = std::vector<Position>;

// Operator overload to print path
std::ostream& operator<<(std::ostream& os, std::vector<Position> const& path) {
for (auto const& pose:path) {
os << "(" << pose.x << ", " << pose.y << ")\n";
}
return os;
for (auto const& pose : path) {
os << "(" << pose.x << ", " << pose.y << ")\n";
}
return os;
}

// Operator overload for position comparison
bool operator==(Position const& lhs, Position const& rhs) {
return lhs.x == rhs.x && lhs.y == rhs.y;
return lhs.x == rhs.x && lhs.y == rhs.y;
}

// From the Robot, goal and costmap, generate a trajectory (Deterministic calculation)
std::optional<Path> generate_global_path(Position const& start, Position const& goal , Map<unsigned char> const& costmap) { // Calculation
// Some cool and nifty algorithm
// What is the delta in position
int const del_x = goal.x - start.x;
int const del_y = goal.y - start.y;

// What direction to move in for each dimension
int const del_x_sign = std::copysign(1.0, del_x);
int const del_y_sign = std::copysign(1.0, del_y);

// Push start onto the path
Path path;
path.push_back(start);

auto is_occupied = [&costmap](auto const x, auto const y) -> bool {
return costmap.at(Position{x, y}) == 1;
};

// Fails if there is any obstacle in the way
// Move horizontally
for (size_t i = 0; i < (std::abs(del_x)); ++i) {
if (is_occupied(path.back().x + del_x_sign, path.back().y)) {
return std::nullopt;
}
path.push_back({path.back().x + del_x_sign, path.back().y});
// From the Robot, goal and costmap, generate a trajectory (Deterministic
// calculation)
std::optional<Path> generate_global_path(
Position const& start, Position const& goal,
Map<unsigned char> const& costmap) { // Calculation
// Some cool and nifty algorithm
// What is the delta in position
int const del_x = goal.x - start.x;
int const del_y = goal.y - start.y;

// What direction to move in for each dimension
int const del_x_sign = std::copysign(1.0, del_x);
int const del_y_sign = std::copysign(1.0, del_y);

// Push start onto the path
Path path;
path.push_back(start);

auto is_occupied = [&costmap](auto const x, auto const y) -> bool {
return costmap.at(Position{x, y}) == 1;
};

// Fails if there is any obstacle in the way
// Move horizontally
for (size_t i = 0; i < (std::abs(del_x)); ++i) {
if (is_occupied(path.back().x + del_x_sign, path.back().y)) {
return std::nullopt;
}
// Move vertically
for (size_t i = 0; i < (std::abs(del_y)); i++) {
// if (costmap.at(Position{path.back().x, path.back().y + del_y_sign}) == 1) {
if (is_occupied(path.back().x, path.back().y + del_y_sign)) {
return std::nullopt;
}
path.push_back({path.back().x, path.back().y + del_y_sign});
path.push_back({path.back().x + del_x_sign, path.back().y});
}
// Move vertically
for (size_t i = 0; i < (std::abs(del_y)); i++) {
// if (costmap.at(Position{path.back().x, path.back().y + del_y_sign}) == 1)
// {
if (is_occupied(path.back().x, path.back().y + del_y_sign)) {
return std::nullopt;
}
path.push_back({path.back().x, path.back().y + del_y_sign});
}

return path;
return path;
}

// test.cc
Expand All @@ -86,64 +88,63 @@ std::optional<Path> generate_global_path(Position const& start, Position const&
* @return The test costmap.
*/
Map<unsigned char> get_test_costmap() {
return {{{0, 0, 0, 0, 0, 0, 0, 0},
{0, 0, 0, 1, 0, 0, 0, 0},
{0, 0, 0, 1, 0, 0, 0, 0},
{0, 0, 1, 1, 1, 0, 0, 0},
{0, 0, 1, 0, 1, 1, 0, 0},
{0, 0, 1, 0, 0, 0, 0, 0},
{0, 0, 0, 0, 0, 0, 0, 0},
{0, 0, 0, 0, 0, 0, 0, 0}}};
return {{{0, 0, 0, 0, 0, 0, 0, 0},
{0, 0, 0, 1, 0, 0, 0, 0},
{0, 0, 0, 1, 0, 0, 0, 0},
{0, 0, 1, 1, 1, 0, 0, 0},
{0, 0, 1, 0, 1, 1, 0, 0},
{0, 0, 1, 0, 0, 0, 0, 0},
{0, 0, 0, 0, 0, 0, 0, 0},
{0, 0, 0, 0, 0, 0, 0, 0}}};
}

TEST(generate_path, same_start_and_goal) {
// GIVEN a costmap and the same start and goal
auto const sample_costmap = get_test_costmap();

// GIVEN a costmap and the same start and goal
auto const sample_costmap = get_test_costmap();
Position const start{0, 0};
Position const goal{0, 0};

Position const start {0, 0};
Position const goal {0, 0};
// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);

// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);

// THEN the path should have one element, which is the start/goal position
std::vector<Position> expected {{0, 0}};
EXPECT_EQ(path.value(), expected) << path.value();
// THEN the path should have one element, which is the start/goal position
std::vector<Position> expected{{0, 0}};
EXPECT_EQ(path.value(), expected) << path.value();
}

TEST(generate_path, no_path) {
// GIVEN a costmap AND a start and goal position
auto const sample_costmap = get_test_costmap();

// GIVEN a costmap AND a start and goal position
auto const sample_costmap = get_test_costmap();

Position const start {2, 2};
Position const goal {5, 5};
Position const start{2, 2};
Position const goal{5, 5};

// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);
// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);

// THEN the path should not have been generated
EXPECT_FALSE(path.has_value()) << path.value();
// THEN the path should not have been generated
EXPECT_FALSE(path.has_value()) << path.value();
}

TEST(generate_path, path_generated) {
// GIVEN a costmap AND a start and goal position
auto const sample_costmap = get_test_costmap();

// GIVEN a costmap AND a start and goal position
auto const sample_costmap = get_test_costmap();

Position const start {0, 0};
Position const goal {7, 7};
Position const start{0, 0};
Position const goal{7, 7};

// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);
// WHEN the global path is produced
auto const& path = generate_global_path(start, goal, sample_costmap);

// THEN the path should have a valid path from start to the goal
std::vector<Position> expected {{0, 0}, {1, 0}, {2, 0}, {3, 0}, {4, 0}, {5, 0}, {6, 0}, {7, 0}, {7, 1}, {7, 2}, {7, 3}, {7, 4}, {7, 5}, {7, 6}, {7, 7}};
EXPECT_EQ(path.value(), expected) << path.value();
// THEN the path should have a valid path from start to the goal
std::vector<Position> expected{{0, 0}, {1, 0}, {2, 0}, {3, 0}, {4, 0},
{5, 0}, {6, 0}, {7, 0}, {7, 1}, {7, 2},
{7, 3}, {7, 4}, {7, 5}, {7, 6}, {7, 7}};
EXPECT_EQ(path.value(), expected) << path.value();
}

int main(int argc, char** argv) {
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
Loading

0 comments on commit 9457301

Please sign in to comment.