diff --git a/nav2_controller/nav2_controller/package.xml b/nav2_controller/nav2_controller/package.xml index ad6b0070ab1..6e479ddbdc4 100644 --- a/nav2_controller/nav2_controller/package.xml +++ b/nav2_controller/nav2_controller/package.xml @@ -6,7 +6,7 @@ ROS2 controller (DWB) metapackage - Oregon Robotics Team + Carl Delsey Steve Macenski Apache License 2.0 diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/array_parser.h b/nav2_costmap_2d/include/nav2_costmap_2d/array_parser.h index 7acc55bb0b9..592e7c53cd2 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/array_parser.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/array_parser.h @@ -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 +#define NAV2_COSTMAP_2D__ARRAY_PARSER_H #include #include @@ -48,4 +48,4 @@ std::vector > 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 diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/cost_values.h b/nav2_costmap_2d/include/nav2_costmap_2d/cost_values.h index 6703f8af3dd..2077250d003 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/cost_values.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/cost_values.h @@ -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 { @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.h b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.h index fea86ae309d..5e3bdc4ce68 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.h @@ -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__COSTMAP_2D_H_ +#define NAV2_COSTMAP_2D__COSTMAP_2D_H_ #include #include @@ -480,4 +480,4 @@ class Costmap2D }; } // namespace nav2_costmap_2d -#endif // nav2_costmap_2d_nav2_costmap_2d_H +#endif // NAV2_COSTMAP_2D__COSTMAP_2D_H diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.h b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.h index 306b33483ac..de21863f45b 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.h @@ -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__COSTMAP_2D_PUBLISHER_H_ +#define NAV2_COSTMAP_2D__COSTMAP_2D_PUBLISHER_H_ #include "rclcpp/rclcpp.hpp" #include @@ -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__COSTMAP_2D_PUBLISHER_H diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.h b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.h index 53ec7d25ead..7f6da395f5c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.h @@ -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__COSTMAP_2D_ROS_H_ +#define NAV2_COSTMAP_2D__COSTMAP_2D_ROS_H_ #include #include @@ -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__COSTMAP_2D_ROS_H diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.h index fc55145f651..378d148de31 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.h @@ -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 #include @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_math.h b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_math.h index 8fee35cafa2..5830d33b436 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_math.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_math.h @@ -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 #include @@ -67,4 +67,4 @@ bool intersects(std::vector & polygon, float testx, f bool intersects(std::vector & polygon1, std::vector & polygon2); -#endif // nav2_costmap_2d_COSTMAP_MATH_H_ +#endif // NAV2_COSTMAP_2D__COSTMAP_MATH_H_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.h b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.h index 7ed44b0b13c..9380cf1341c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.h @@ -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 @@ -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 diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.h index f62171f9750..13ca14a2b50 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/inflation_layer.h @@ -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 #include @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/layer.h index 4d1d6271f28..1f03e83e968 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layer.h @@ -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 #include @@ -132,4 +132,4 @@ class Layer } // namespace nav2_costmap_2d -#endif // nav2_costmap_2d_LAYER_H_ +#endif // NAV2_COSTMAP_2D__LAYER_H_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.h b/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.h index 12d7faa82da..9435391e61b 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layered_costmap.h @@ -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 #include @@ -175,4 +175,4 @@ class LayeredCostmap } // namespace nav2_costmap_2d -#endif // nav2_costmap_2d_LAYERED_COSTMAP_H_ +#endif // NAV2_COSTMAP_2D__LAYERED_COSTMAP_H_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/observation.h b/nav2_costmap_2d/include/nav2_costmap_2d/observation.h index f1445bf4e0d..beb3dc39710 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/observation.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/observation.h @@ -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 #include @@ -100,4 +100,4 @@ class Observation }; } // namespace nav2_costmap_2d -#endif // nav2_costmap_2d_OBSERVATION_H_ +#endif // NAV2_COSTMAP_2D__OBSERVATION_H_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.h b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.h index 98d24f0e2e7..d5405075439 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.h @@ -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 #include @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.h index 1b11d164f86..87944b52a8e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.h @@ -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 #include @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.h index aacd2c48b02..4590d37a354 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.h @@ -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 #include @@ -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_ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.h b/nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.h index 759ec536913..00529027be4 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/testing_helper.h @@ -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 @@ -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 diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.h b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.h index 5b6a04ccc43..301d1e97a2a 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.h +++ b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.h @@ -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 #include @@ -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_