Skip to content

Commit

Permalink
fixed uncrustify
Browse files Browse the repository at this point in the history
revert dwb_critics cmake changes
  • Loading branch information
bpwilcox committed May 18, 2019
1 parent c3778c7 commit 3f904d7
Show file tree
Hide file tree
Showing 10 changed files with 36 additions and 43 deletions.
4 changes: 2 additions & 2 deletions nav2_costmap_2d/include/nav2_costmap_2d/collision_checker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class CollisionChecker
std::shared_ptr<FootprintSubscriber> footprint_sub,
tf2_ros::Buffer & tf_buffer,
std::string name = "collision_checker");

~CollisionChecker();

double scorePose(
Expand All @@ -70,7 +70,7 @@ class CollisionChecker
rclcpp::Node::SharedPtr node_;
std::string name_;
std::shared_ptr<CostmapSubscriber> costmap_sub_;
std::shared_ptr<FootprintSubscriber> footprint_sub_;
std::shared_ptr<FootprintSubscriber> footprint_sub_;
};
} // namespace nav2_costmap_2d

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class Costmap2DPublisher
rclcpp::Publisher<map_msgs::msg::OccupancyGridUpdate>::SharedPtr costmap_update_pub_;

nav_msgs::msg::OccupancyGrid grid_;
nav2_msgs::msg::Costmap costmap_raw_;
nav2_msgs::msg::Costmap costmap_raw_;
// Translate from 0-255 values in costmap to -1 to 100 values in message.
static char * cost_translation_table_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class CostmapSubscriber
std::string & topic_name);
~CostmapSubscriber() {}

Costmap2D * getCostmap();
Costmap2D * getCostmap();

protected:
void toCostmap2D();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class FootprintSubscriber
std::string & topic_name);
~FootprintSubscriber() {}

bool getFootprint(std::vector<geometry_msgs::msg::Point> & footprint);
bool getFootprint(std::vector<geometry_msgs::msg::Point> & footprint);

protected:
void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg);
Expand Down
11 changes: 5 additions & 6 deletions nav2_costmap_2d/src/collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ CollisionChecker::CollisionChecker(
CollisionChecker::~CollisionChecker() {}

bool CollisionChecker::isCollisionFree(
const geometry_msgs::msg::Pose2D & pose)
const geometry_msgs::msg::Pose2D & pose)
{
try {
if (scorePose(pose) < 0) {
Expand All @@ -57,7 +57,7 @@ const geometry_msgs::msg::Pose2D & pose)
}

double CollisionChecker::scorePose(
const geometry_msgs::msg::Pose2D & pose)
const geometry_msgs::msg::Pose2D & pose)
{
Costmap2D * costmap_;
try {
Expand Down Expand Up @@ -107,13 +107,13 @@ const geometry_msgs::msg::Pose2D & pose)
// we also need to connect the first point in the footprint to the last point
// get the cell coord of the last point
if (!costmap_->worldToMap(footprint.back().x, footprint.back().y, x0, y0)) {
RCLCPP_DEBUG(node_->get_logger(), "Map Cell: [%d, %d]", x0, y0);
RCLCPP_DEBUG(node_->get_logger(), "Map Cell: [%d, %d]", x0, y0);
throw IllegalPoseException(name_, "Footprint Goes Off Grid.");
}

// get the cell coord of the first point
if (!costmap_->worldToMap(footprint.front().x, footprint.front().y, x1, y1)) {
RCLCPP_DEBUG(node_->get_logger(), "Map Cell: [%d, %d]", x1, y1);
RCLCPP_DEBUG(node_->get_logger(), "Map Cell: [%d, %d]", x1, y1);
throw IllegalPoseException(name_, "Footprint Goes Off Grid.");
}

Expand Down Expand Up @@ -193,7 +193,7 @@ void CollisionChecker::unorientFootprint(
std::vector<geometry_msgs::msg::Point> & reset_footprint)
{
geometry_msgs::msg::PoseStamped current_pose;
if (!getRobotPose(current_pose)) {
if (!getRobotPose(current_pose)) {
throw CollisionCheckerException("Robot pose unavailable.");
}

Expand All @@ -207,4 +207,3 @@ void CollisionChecker::unorientFootprint(
}

} // namespace nav2_costmap_2d

8 changes: 4 additions & 4 deletions nav2_costmap_2d/src/costmap_2d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,9 @@ Costmap2DPublisher::Costmap2DPublisher(

// TODO(bpwilcox): port onNewSubscription functionality for publisher
costmap_pub_ = ros_node->create_publisher<nav_msgs::msg::OccupancyGrid>(topic_name,
custom_qos_profile);
custom_qos_profile);
costmap_raw_pub_ = ros_node->create_publisher<nav2_msgs::msg::Costmap>(topic_name + "_raw",
custom_qos_profile);
custom_qos_profile);
costmap_update_pub_ = ros_node->create_publisher<map_msgs::msg::OccupancyGridUpdate>(
topic_name + "_updates", custom_qos_profile);

Expand Down Expand Up @@ -161,12 +161,12 @@ void Costmap2DPublisher::prepareCostmap()
void Costmap2DPublisher::publishCostmap()
{
if (node_->count_subscribers(topic_name_) == 0 &&
node_->count_subscribers(topic_name_ + "_raw") == 0)
node_->count_subscribers(topic_name_ + "_raw") == 0)
{
// No subscribers, so why do any work?
return;
}
// Always publish raw costmap
// Always publish raw costmap
prepareCostmap();
costmap_raw_pub_->publish(costmap_raw_);

Expand Down
11 changes: 5 additions & 6 deletions nav2_costmap_2d/src/costmap_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,16 +43,16 @@ void CostmapSubscriber::toCostmap2D()
{
if (!costmap_received_) {
costmap_ = new Costmap2D(
msg_->metadata.size_x, msg_->metadata.size_y,
msg_->metadata.resolution, msg_->metadata.origin.position.x,
msg_->metadata.origin.position.y);
msg_->metadata.size_x, msg_->metadata.size_y,
msg_->metadata.resolution, msg_->metadata.origin.position.x,
msg_->metadata.origin.position.y);
} else if (costmap_->getSizeInCellsX() != msg_->metadata.size_x ||
costmap_->getSizeInCellsY() != msg_->metadata.size_y ||
costmap_->getResolution() != msg_->metadata.resolution ||
costmap_->getOriginX() != msg_->metadata.origin.position.x ||
costmap_->getOriginY() != msg_->metadata.origin.position.y)
{
// Update the size of the costmap
// Update the size of the costmap
costmap_->resizeMap(msg_->metadata.size_x, msg_->metadata.size_y,
msg_->metadata.resolution,
msg_->metadata.origin.position.x,
Expand All @@ -61,7 +61,7 @@ void CostmapSubscriber::toCostmap2D()

unsigned char * master_array = costmap_->getCharMap();
unsigned int index = 0;
for (unsigned int i = 0; i < msg_->metadata.size_x; ++i) {
for (unsigned int i = 0; i < msg_->metadata.size_x; ++i) {
for (unsigned int j = 0; j < msg_->metadata.size_y; ++j) {
master_array[index] = msg_->data[index];
++index;
Expand All @@ -79,4 +79,3 @@ void CostmapSubscriber::costmap_callback(const nav2_msgs::msg::Costmap::SharedPt
}

} // namespace nav2_costmap_2d

1 change: 0 additions & 1 deletion nav2_costmap_2d/src/footprint_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,4 +50,3 @@ FootprintSubscriber::footprint_callback(const geometry_msgs::msg::PolygonStamped
}

} // namespace nav2_costmap_2d

34 changes: 17 additions & 17 deletions nav2_costmap_2d/test/integration/test_collision_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,24 +72,23 @@ class TestCollisionChecker : public nav2_costmap_2d::CollisionChecker

costmap_pub_ = std::make_unique<nav2_costmap_2d::Costmap2DPublisher>(node_,
layers_.getCostmap(), global_frame_, "costmap", true);

publish();
}

~TestCollisionChecker() {}

bool testPose(double x,double y, double theta)
bool testPose(double x, double y, double theta)
{
geometry_msgs::msg::Pose2D pose;
pose.x = x;
pose.y = y;
pose.theta = theta;

setPose(x,y,theta);
setPose(x, y, theta);
costmap_received_ = false;

while(!costmap_received_)
{
while (!costmap_received_) {
rclcpp::spin_some(node_);
}

Expand Down Expand Up @@ -129,19 +128,19 @@ class TestCollisionChecker : public nav2_costmap_2d::CollisionChecker

void publish()
{
auto timer_callback = [this]() -> void
{
try {
costmap_sub_->getCostmap();
costmap_received_ = true;
} catch (const std::runtime_error & e) {
costmap_received_ = false;
}
auto timer_callback = [this]() -> void
{
try {
costmap_sub_->getCostmap();
costmap_received_ = true;
} catch (const std::runtime_error & e) {
costmap_received_ = false;
}
publishFootprint();
publishCostmap();
};
};

timer_ = node_->create_wall_timer(0.1s, timer_callback);
timer_ = node_->create_wall_timer(0.1s, timer_callback);
}

void publishFootprint()
Expand Down Expand Up @@ -180,7 +179,7 @@ class TestNode : public ::testing::Test

node_ = rclcpp::Node::make_shared(
"test_collision_checker", nav2_util::get_node_options_default());

tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);

Expand All @@ -189,7 +188,8 @@ class TestNode : public ::testing::Test
costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node_, costmap_topic);
footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(node_, footprint_topic);

collision_checker_ = std::make_unique<TestCollisionChecker>(node_, costmap_sub_, footprint_sub_, *tf_buffer_);
collision_checker_ = std::make_unique<TestCollisionChecker>(node_, costmap_sub_, footprint_sub_,
*tf_buffer_);
}

~TestNode() {}
Expand Down
4 changes: 0 additions & 4 deletions nav2_dwb_controller/dwb_critics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,14 +71,10 @@ if(BUILD_TESTING)
# the following line skips the linter which checks for copyrights
set(ament_cmake_copyright_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
find_package(ament_cmake_pytest REQUIRED)
find_package(ament_cmake_gtest REQUIRED)
endif()

ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})


ament_export_dependencies(
${dependencies}
)
Expand Down

0 comments on commit 3f904d7

Please sign in to comment.