Skip to content

Commit

Permalink
costmap_cspace: install header files (#155)
Browse files Browse the repository at this point in the history
  • Loading branch information
at-wat committed May 16, 2018
1 parent c5cce44 commit e2c57c7
Show file tree
Hide file tree
Showing 15 changed files with 51 additions and 50 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,17 +27,17 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_H
#define COSTMAP_3D_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_H
#define COSTMAP_CSPACE_COSTMAP_3D_H

#include <ros/ros.h>

#include <costmap_3d_layer/footprint.h>
#include <costmap_3d_layer/plain.h>
#include <costmap_3d_layer/output.h>
#include <costmap_3d_layer/unknown_handle.h>
#include <costmap_cspace/costmap_3d_layer/footprint.h>
#include <costmap_cspace/costmap_3d_layer/plain.h>
#include <costmap_cspace/costmap_3d_layer/output.h>
#include <costmap_cspace/costmap_3d_layer/unknown_handle.h>

#include <costmap_3d_layer/class_loader.h>
#include <costmap_cspace/costmap_3d_layer/class_loader.h>

#include <vector>

Expand Down Expand Up @@ -105,4 +105,4 @@ class Costmap3d
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_BASE_H
#define COSTMAP_3D_LAYER_BASE_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H

#include <ros/ros.h>

Expand Down Expand Up @@ -389,4 +389,4 @@ class Costmap3dLayerBase
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_BASE_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_CLASS_LOADER_H
#define COSTMAP_3D_LAYER_CLASS_LOADER_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H

#include <ros/ros.h>

Expand All @@ -37,8 +37,8 @@
#include <costmap_cspace/CSpace3D.h>
#include <costmap_cspace/CSpace3DUpdate.h>

#include <cspace3_cache.h>
#include <polygon.h>
#include <costmap_cspace/cspace3_cache.h>
#include <costmap_cspace/polygon.h>

#include <string>
#include <map>
Expand Down Expand Up @@ -102,4 +102,4 @@ class Costmap3dLayerClassLoader

} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_CLASS_LOADER_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_CLASS_LOADER_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_FOOTPRINT_H
#define COSTMAP_3D_LAYER_FOOTPRINT_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H

#include <ros/ros.h>

Expand All @@ -39,9 +39,9 @@

#include <xmlrpcpp/XmlRpcValue.h>

#include <costmap_3d_layer/base.h>
#include <cspace3_cache.h>
#include <polygon.h>
#include <costmap_cspace/costmap_3d_layer/base.h>
#include <costmap_cspace/cspace3_cache.h>
#include <costmap_cspace/polygon.h>

namespace costmap_cspace
{
Expand Down Expand Up @@ -262,4 +262,4 @@ class Costmap3dLayerFootprint : public Costmap3dLayerBase
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_FOOTPRINT_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_OUTPUT_H
#define COSTMAP_3D_LAYER_OUTPUT_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H

#include <geometry_msgs/PolygonStamped.h>
#include <nav_msgs/OccupancyGrid.h>
#include <costmap_cspace/CSpace3D.h>
#include <costmap_cspace/CSpace3DUpdate.h>

#include <costmap_3d_layer/base.h>
#include <costmap_cspace/costmap_3d_layer/base.h>

namespace costmap_cspace
{
Expand Down Expand Up @@ -148,4 +148,4 @@ class Costmap3dLayerOutput : public Costmap3dLayerBase
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_OUTPUT_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_PLAIN_H
#define COSTMAP_3D_LAYER_PLAIN_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_PLAIN_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_PLAIN_H

#include <geometry_msgs/PolygonStamped.h>
#include <nav_msgs/OccupancyGrid.h>
#include <costmap_cspace/CSpace3D.h>
#include <costmap_cspace/CSpace3DUpdate.h>

#include <costmap_3d_layer/base.h>
#include <costmap_cspace/costmap_3d_layer/base.h>

namespace costmap_cspace
{
Expand Down Expand Up @@ -63,4 +63,4 @@ class Costmap3dLayerPlain : public Costmap3dLayerFootprint
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_PLAIN_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_PLAIN_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
#define COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
#ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
#define COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H

#include <geometry_msgs/PolygonStamped.h>
#include <nav_msgs/OccupancyGrid.h>
#include <costmap_cspace/CSpace3D.h>
#include <costmap_cspace/CSpace3DUpdate.h>

#include <costmap_3d_layer/base.h>
#include <costmap_cspace/costmap_3d_layer/base.h>

namespace costmap_cspace
{
Expand Down Expand Up @@ -101,4 +101,4 @@ class Costmap3dLayerUnknownHandle : public Costmap3dLayerBase
};
} // namespace costmap_cspace

#endif // COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
#endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef CSPACE3_CACHE_H
#define CSPACE3_CACHE_H
#ifndef COSTMAP_CSPACE_CSPACE3_CACHE_H
#define COSTMAP_CSPACE_CSPACE3_CACHE_H

#include <ros/ros.h>

Expand Down Expand Up @@ -97,4 +97,4 @@ class CSpace3Cache
};
} // namespace costmap_cspace

#endif // CSPACE3_CACHE_H
#endif // COSTMAP_CSPACE_CSPACE3_CACHE_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H
#define POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H
#ifndef COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H
#define COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H

#include <ros/ros.h>

Expand All @@ -44,7 +44,8 @@ class PointcloudAccumurator
ros::Time stamp_;

Points(const T &points, const ros::Time &stamp)
: T(points), stamp_(stamp)
: T(points)
, stamp_(stamp)
{
}
};
Expand Down Expand Up @@ -97,4 +98,4 @@ class PointcloudAccumurator
std::list<Points> points_;
};

#endif // POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H
#endif // COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef POLYGON_H
#define POLYGON_H
#ifndef COSTMAP_CSPACE_POLYGON_H
#define COSTMAP_CSPACE_POLYGON_H

#include <ros/ros.h>
#include <vector>
Expand Down Expand Up @@ -107,7 +107,7 @@ class Polygon
p[0] = static_cast<double>(footprint_xml[i][0]);
p[1] = static_cast<double>(footprint_xml[i][1]);
}
catch(XmlRpc::XmlRpcException &e)
catch (XmlRpc::XmlRpcException &e)
{
throw std::runtime_error(("Invalid footprint xml." + e.getMessage()).c_str());
}
Expand Down Expand Up @@ -190,4 +190,4 @@ class Polygon
};
} // namespace costmap_cspace

#endif // POLYGON_H
#endif // COSTMAP_CSPACE_POLYGON_H
2 changes: 1 addition & 1 deletion costmap_cspace/src/costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <costmap_cspace/CSpace3D.h>
#include <costmap_cspace/CSpace3DUpdate.h>

#include <costmap_3d.h>
#include <costmap_cspace/costmap_3d.h>

class Costmap3DOFNode
{
Expand Down
2 changes: 1 addition & 1 deletion costmap_cspace/src/costmap_3d_layers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include <string>
#include <vector>

#include <costmap_3d.h>
#include <costmap_cspace/costmap_3d.h>

COSTMAP_3D_LAYER_CLASS_LOADER_ENABLE();

Expand Down
2 changes: 1 addition & 1 deletion costmap_cspace/src/laserscan_to_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#include <string>

#include <pointcloud_accumulator/accumulator.h>
#include <costmap_cspace/pointcloud_accumulator/accumulator.h>

class laserscan_to_map
{
Expand Down
2 changes: 1 addition & 1 deletion costmap_cspace/src/pointcloud2_to_map.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include <string>
#include <vector>

#include <pointcloud_accumulator/accumulator.h>
#include <costmap_cspace/pointcloud_accumulator/accumulator.h>

class pointcloud2_to_map
{
Expand Down
2 changes: 1 addition & 1 deletion costmap_cspace/test/src/test_costmap_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

#include <ros/ros.h>
#include <nav_msgs/OccupancyGrid.h>
#include <costmap_3d.h>
#include <costmap_cspace/costmap_3d.h>

const std::string footprint_str(
"<value><array><data>"
Expand Down

0 comments on commit e2c57c7

Please sign in to comment.