Skip to content

Commit

Permalink
install-related fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
gerkey committed Jan 12, 2012
1 parent f180651 commit 08fa205
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 9 deletions.
1 change: 0 additions & 1 deletion geometry_msgs/manifest.xml
Expand Up @@ -15,7 +15,6 @@
<depend package="rosbagmigration"/>
<depend package="rosbag"/>
<export>
<cpp cflags=""/>
<rosbag migration_rule_file="migration_rules/geometry_msgs.bmr"/>
</export>

Expand Down
16 changes: 9 additions & 7 deletions sensor_msgs/CMakeLists.txt
@@ -1,4 +1,8 @@
project(sensor_msgs)
catkin_project(sensor_msgs
LIBRARIES sensor_msgs
INCLUDE_DIRS include
)

include_directories(include)

Expand All @@ -20,10 +24,8 @@ add_service_files(

generate_messages(DEPENDENCIES std_msgs geometry_msgs)

catkin_project(sensor_msgs
)

message("TODO: re-enable sensor_msgs library")
#add_library(${PROJECT_NAME}
# src/image_encodings.cpp src/point_cloud_conversion.cpp src/distortion_models.cpp
# )
add_library(sensor_msgs SHARED
src/image_encodings.cpp src/point_cloud_conversion.cpp src/distortion_models.cpp
)
install(TARGETS sensor_msgs
LIBRARY DESTINATION lib)
3 changes: 2 additions & 1 deletion sensor_msgs/manifest.xml
Expand Up @@ -11,7 +11,8 @@ cameras and scanning laser rangefinders.
<url>http://ros.org/wiki/sensor_msgs</url>

<export>
<cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lsensor_msgs -Wl,-rpath,${prefix}/lib"/>
<cpp cflags="`PKG_CONFIG_PATH=${prefix}/../../lib/pkgconfig pkg-config --cflags sensor_msgs`"
lflags="`PKG_CONFIG_PATH=${prefix}/../../lib/pkgconfig pkg-config --libs sensor_msgs`"/>
<rosbag migration_rule_file="migration_rules/sensor_msgs.bmr"/>
</export>

Expand Down

0 comments on commit 08fa205

Please sign in to comment.