Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_controller/nav2_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<description>
ROS2 controller (DWB) metapackage
</description>
<maintainer email="oregon.robotics.team@intel.com">Oregon Robotics Team</maintainer>
<maintainer email="carl.r.delsey@intel.com">Carl Delsey</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache License 2.0</license>

Expand Down
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/array_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@
*
* author: Dave Hershberger
*/
#ifndef nav2_costmap_2d_ARRAY_PARSER_H
#define nav2_costmap_2d_ARRAY_PARSER_H
#ifndef NAV2_COSTMAP_2D_ARRAY_PARSER_H
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this pass cpplint? I thought it wanted two _ between the path and the filename part eg NAV2_COSTMAP_2D__ARRAY_PARSER_H

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This directory has a lot of issues still w/ the linters. Since the spirit of this PR was directory re-org, I suggest leaving that for a separate PR.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

fixed all to have double underscores.

#define NAV2_COSTMAP_2D_ARRAY_PARSER_H

#include <vector>
#include <string>
Expand All @@ -48,4 +48,4 @@ std::vector<std::vector<float> > parseVVF(const std::string & input, std::string

} // end namespace nav2_costmap_2d

#endif // nav2_costmap_2d_ARRAY_PARSER_H
#endif // NAV2_COSTMAP_2D_ARRAY_PARSER_H
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/cost_values.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
*
* Author: Eitan Marder-Eppstein
*********************************************************************/
#ifndef nav2_costmap_2d_COST_VALUES_H_
#define nav2_costmap_2d_COST_VALUES_H_
#ifndef NAV2_COSTMAP_2D_COST_VALUES_H_
#define NAV2_COSTMAP_2D_COST_VALUES_H_
/** Provides a mapping for often used cost values */
namespace nav2_costmap_2d
{
Expand All @@ -44,4 +44,4 @@ static const unsigned char LETHAL_OBSTACLE = 254;
static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
static const unsigned char FREE_SPACE = 0;
}
#endif // nav2_costmap_2d_COST_VALUES_H_
#endif // NAV2_COSTMAP_2D_COST_VALUES_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_nav2_costmap_2d_H_
#define nav2_costmap_2d_nav2_costmap_2d_H_
#ifndef NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_H_
#define NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_H_

#include <cmath>
#include <vector>
Expand Down Expand Up @@ -480,4 +480,4 @@ class Costmap2D
};
} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_nav2_costmap_2d_H
#endif // NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_H
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_nav2_costmap_2d_PUBLISHER_H_
#define nav2_costmap_2d_nav2_costmap_2d_PUBLISHER_H_
#ifndef NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_PUBLISHER_H_
#define NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_PUBLISHER_H_

#include "rclcpp/rclcpp.hpp"
#include <nav2_costmap_2d/costmap_2d.h>
Expand Down Expand Up @@ -110,4 +110,4 @@ class Costmap2DPublisher
static char * cost_translation_table_; ///< Translate from 0-255 values in costmap to -1 to 100 values in message.
};
} // namespace nav2_costmap_2d
#endif // nav2_costmap_2d_nav2_costmap_2d_PUBLISHER_H
#endif // NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_PUBLISHER_H
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_nav2_costmap_2d_ROS_H_
#define nav2_costmap_2d_nav2_costmap_2d_ROS_H_
#ifndef NAV2_COSTMAP_2D_nav2_costmap_2d_ROS_H_
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this should be NAV2_COSTMAP_2D__COSTMAP_2D_ROS_H_ That is, uppercase filename part, no nav2 prefix on the filename part and double underscores.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@SteveMacenski - can you please make this change and we can get this approved

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

#define NAV2_COSTMAP_2D_nav2_costmap_2d_ROS_H_

#include <nav2_costmap_2d/layered_costmap.h>
#include <nav2_costmap_2d/layer.h>
Expand Down Expand Up @@ -286,4 +286,4 @@ class Costmap2DROS
// class Costmap2DROS
} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_nav2_costmap_2d_ROS_H
#endif // NAV2_COSTMAP_2D_NAV2_COSTMAP_2D_ROS_H
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_COSTMAP_LAYER_H_
#define nav2_costmap_2d_COSTMAP_LAYER_H_
#ifndef NAV2_COSTMAP_2D_COSTMAP_LAYER_H_
#define NAV2_COSTMAP_2D_COSTMAP_LAYER_H_

#include <rclcpp/rclcpp.hpp>
#include <nav2_costmap_2d/layer.h>
Expand Down Expand Up @@ -151,4 +151,4 @@ class CostmapLayer : public Layer, public Costmap2D
};

} // namespace nav2_costmap_2d
#endif // nav2_costmap_2d_COSTMAP_LAYER_H_
#endif // NAV2_COSTMAP_2D_COSTMAP_LAYER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/costmap_math.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_COSTMAP_MATH_H_
#define nav2_costmap_2d_COSTMAP_MATH_H_
#ifndef NAV2_COSTMAP_2D_COSTMAP_MATH_H_
#define NAV2_COSTMAP_2D_COSTMAP_MATH_H_

#include <math.h>
#include <algorithm>
Expand Down Expand Up @@ -67,4 +67,4 @@ bool intersects(std::vector<geometry_msgs::msg::Point> & polygon, float testx, f
bool intersects(std::vector<geometry_msgs::msg::Point> & polygon1,
std::vector<geometry_msgs::msg::Point> & polygon2);

#endif // nav2_costmap_2d_COSTMAP_MATH_H_
#endif // NAV2_COSTMAP_2D_COSTMAP_MATH_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/footprint.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_FOOTPRINT_H
#define nav2_costmap_2d_FOOTPRINT_H
#ifndef NAV2_COSTMAP_2D_FOOTPRINT_H
#define NAV2_COSTMAP_2D_FOOTPRINT_H

#include "rclcpp/rclcpp.hpp"
#include <geometry_msgs/msg/polygon.hpp>
Expand Down Expand Up @@ -150,4 +150,4 @@ void writeFootprintToParam(rclcpp::Node::SharedPtr nh,

} // end namespace nav2_costmap_2d

#endif // nav2_costmap_2d_FOOTPRINT_H
#endif // NAV2_COSTMAP_2D_FOOTPRINT_H
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_INFLATION_LAYER_H_
#define nav2_costmap_2d_INFLATION_LAYER_H_
#ifndef NAV2_COSTMAP_2D_INFLATION_LAYER_H_
#define NAV2_COSTMAP_2D_INFLATION_LAYER_H_

#include <rclcpp/rclcpp.hpp>
#include <nav2_costmap_2d/layer.h>
Expand Down Expand Up @@ -197,4 +197,4 @@ class InflationLayer : public Layer

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_INFLATION_LAYER_H_
#endif // NAV2_COSTMAP_2D_INFLATION_LAYER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
*
* Author: David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_LAYER_H_
#define nav2_costmap_2d_LAYER_H_
#ifndef NAV2_COSTMAP_2D_LAYER_H_
#define NAV2_COSTMAP_2D_LAYER_H_

#include <nav2_costmap_2d/costmap_2d.h>
#include <nav2_costmap_2d/layered_costmap.h>
Expand Down Expand Up @@ -132,4 +132,4 @@ class Layer

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_LAYER_H_
#endif // NAV2_COSTMAP_2D_LAYER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_LAYERED_COSTMAP_H_
#define nav2_costmap_2d_LAYERED_COSTMAP_H_
#ifndef NAV2_COSTMAP_2D_LAYERED_COSTMAP_H_
#define NAV2_COSTMAP_2D_LAYERED_COSTMAP_H_

#include <nav2_costmap_2d/cost_values.h>
#include <nav2_costmap_2d/layer.h>
Expand Down Expand Up @@ -175,4 +175,4 @@ class LayeredCostmap

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_LAYERED_COSTMAP_H_
#endif // NAV2_COSTMAP_2D_LAYERED_COSTMAP_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/observation.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@
* Authors: Conor McGann
*/

#ifndef nav2_costmap_2d_OBSERVATION_H_
#define nav2_costmap_2d_OBSERVATION_H_
#ifndef NAV2_COSTMAP_2D_OBSERVATION_H_
#define NAV2_COSTMAP_2D_OBSERVATION_H_

#include <geometry_msgs/msg/point.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down Expand Up @@ -100,4 +100,4 @@ class Observation
};

} // namespace nav2_costmap_2d
#endif // nav2_costmap_2d_OBSERVATION_H_
#endif // NAV2_COSTMAP_2D_OBSERVATION_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@
*
* Author: Eitan Marder-Eppstein
*********************************************************************/
#ifndef nav2_costmap_2d_OBSERVATION_BUFFER_H_
#define nav2_costmap_2d_OBSERVATION_BUFFER_H_
#ifndef NAV2_COSTMAP_2D_OBSERVATION_BUFFER_H_
#define NAV2_COSTMAP_2D_OBSERVATION_BUFFER_H_

#include <vector>
#include <list>
Expand Down Expand Up @@ -152,4 +152,4 @@ class ObservationBuffer
double tf_tolerance_;
};
} // namespace nav2_costmap_2d
#endif // nav2_costmap_2d_OBSERVATION_BUFFER_H_
#endif // NAV2_COSTMAP_2D_OBSERVATION_BUFFER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_OBSTACLE_LAYER_H_
#define nav2_costmap_2d_OBSTACLE_LAYER_H_
#ifndef NAV2_COSTMAP_2D_OBSTACLE_LAYER_H_
#define NAV2_COSTMAP_2D_OBSTACLE_LAYER_H_

#include <ros/ros.h>
#include <nav2_costmap_2d/costmap_layer.h>
Expand Down Expand Up @@ -183,4 +183,4 @@ class ObstacleLayer : public CostmapLayer

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_OBSTACLE_LAYER_H_
#endif // NAV2_COSTMAP_2D_OBSTACLE_LAYER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_STATIC_LAYER_H_
#define nav2_costmap_2d_STATIC_LAYER_H_
#ifndef NAV2_COSTMAP_2D_STATIC_LAYER_H_
#define NAV2_COSTMAP_2D_STATIC_LAYER_H_

#include <rclcpp/rclcpp.hpp>
#include <nav2_costmap_2d/costmap_layer.h>
Expand Down Expand Up @@ -104,4 +104,4 @@ class StaticLayer : public CostmapLayer

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_STATIC_LAYER_H_
#endif // NAV2_COSTMAP_2D_STATIC_LAYER_H_
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#ifndef nav2_costmap_2d_TESTING_HELPER_H
#define nav2_costmap_2d_TESTING_HELPER_H
#ifndef NAV2_COSTMAP_2D_TESTING_HELPER_H
#define NAV2_COSTMAP_2D_TESTING_HELPER_H

#include "rclcpp/rclcpp.hpp"
#include <nav2_costmap_2d/cost_values.h>
Expand Down Expand Up @@ -108,4 +108,4 @@ nav2_costmap_2d::InflationLayer * addInflationLayer(nav2_costmap_2d::LayeredCost
}


#endif // nav2_costmap_2d_TESTING_HELPER_H
#endif // NAV2_COSTMAP_2D_TESTING_HELPER_H
6 changes: 3 additions & 3 deletions nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
* Author: Eitan Marder-Eppstein
* David V. Lu!!
*********************************************************************/
#ifndef nav2_costmap_2d_VOXEL_LAYER_H_
#define nav2_costmap_2d_VOXEL_LAYER_H_
#ifndef NAV2_COSTMAP_2D_VOXEL_LAYER_H_
#define NAV2_COSTMAP_2D_VOXEL_LAYER_H_

#include <ros/ros.h>
#include <nav2_costmap_2d/layer.h>
Expand Down Expand Up @@ -158,4 +158,4 @@ class VoxelLayer : public ObstacleLayer

} // namespace nav2_costmap_2d

#endif // nav2_costmap_2d_VOXEL_LAYER_H_
#endif // NAV2_COSTMAP_2D_VOXEL_LAYER_H_