Skip to content

Commit

Permalink
update macro names (#2)
Browse files Browse the repository at this point in the history
  • Loading branch information
kejxu committed Jul 16, 2019
1 parent 21a8041 commit 6db1c8f
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
12 changes: 6 additions & 6 deletions image_geometry/include/image_geometry/exports.h
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
#ifndef IMG_GEO_EXPORTDECL_H
#define IMG_GEO_EXPORTDECL_H
#ifndef IMAGE_GEOMETRY_EXPORTS_H
#define IMAGE_GEOMETRY_EXPORTS_H

#include <ros/macros.h>

// Import/export for windows dll's and visibility for gcc shared libraries.

#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
#ifdef image_geometry_EXPORTS // we are building a shared lib/dll
#define IMG_GEO_DECL ROS_HELPER_EXPORT
#define IMAGE_GEOMETRY_DECL ROS_HELPER_EXPORT
#else // we are using shared lib/dll
#define IMG_GEO_DECL ROS_HELPER_IMPORT
#define IMAGE_GEOMETRY_DECL ROS_HELPER_IMPORT
#endif
#else // ros is being built around static libraries
#define IMG_GEO_DECL
#define IMAGE_GEOMETRY_DECL
#endif

#endif // IMG_GEO_EXPORTDECL_H
#endif // IMAGE_GEOMETRY_EXPORTS_H
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class Exception : public std::runtime_error
* \brief Simplifies interpreting images geometrically using the parameters from
* sensor_msgs/CameraInfo.
*/
class IMG_GEO_DECL PinholeCameraModel
class IMAGE_GEOMETRY_DECL PinholeCameraModel
{
public:

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ namespace image_geometry {
* \brief Simplifies interpreting stereo image pairs geometrically using the
* parameters from the left and right sensor_msgs/CameraInfo.
*/
class IMG_GEO_DECL StereoCameraModel
class IMAGE_GEOMETRY_DECL StereoCameraModel
{
public:
StereoCameraModel();
Expand Down

0 comments on commit 6db1c8f

Please sign in to comment.