refactor naming and fix nodelet export
This commit is contained in:
parent
a41d54b3eb
commit
a70e770af5
@ -13,7 +13,7 @@ find_package(PCL REQUIRED)
|
|||||||
|
|
||||||
catkin_package(
|
catkin_package(
|
||||||
INCLUDE_DIRS include
|
INCLUDE_DIRS include
|
||||||
LIBRARIES PointCloudToLaserScan PointCloudToLaserScanNodelet
|
LIBRARIES pointcloud_to_laserscan
|
||||||
CATKIN_DEPENDS dynamic_reconfigure libpcl-all-dev message_filters nodelet pcl_ros roscpp sensor_msgs
|
CATKIN_DEPENDS dynamic_reconfigure libpcl-all-dev message_filters nodelet pcl_ros roscpp sensor_msgs
|
||||||
)
|
)
|
||||||
|
|
||||||
@ -22,16 +22,13 @@ include_directories(
|
|||||||
${catkin_INCLUDE_DIRS}
|
${catkin_INCLUDE_DIRS}
|
||||||
)
|
)
|
||||||
|
|
||||||
add_library(PointCloudToLaserScan src/PointCloudToLaserScanBase.cpp)
|
add_library(pointcloud_to_laserscan src/pointcloud_to_laserscan_base.cpp src/pointcloud_to_laserscan_nodelet.cpp)
|
||||||
target_link_libraries(PointCloudToLaserScan ${catkin_LIBRARIES})
|
target_link_libraries(pointcloud_to_laserscan ${catkin_LIBRARIES})
|
||||||
|
|
||||||
add_library(PointCloudToLaserScanNodelet src/PointCloudToLaserScanNodelet.cpp)
|
add_executable(pointcloud_to_laserscan_node src/pointcloud_to_laserscan_node.cpp)
|
||||||
target_link_libraries(PointCloudToLaserScanNodelet PointCloudToLaserScan ${catkin_LIBRARIES})
|
target_link_libraries(pointcloud_to_laserscan_node pointcloud_to_laserscan ${catkin_LIBRARIES})
|
||||||
|
|
||||||
add_executable(pointcloud_to_laserscan src/pointcloud_to_laserscan_node.cpp)
|
install(TARGETS pointcloud_to_laserscan pointcloud_to_laserscan_node
|
||||||
target_link_libraries(pointcloud_to_laserscan PointCloudToLaserScan ${catkin_LIBRARIES})
|
|
||||||
|
|
||||||
install(TARGETS PointCloudToLaserScan PointCloudToLaserScanNodelet pointcloud_to_laserscan
|
|
||||||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
||||||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
||||||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
|
||||||
|
|||||||
@ -10,7 +10,7 @@
|
|||||||
</include>
|
</include>
|
||||||
|
|
||||||
<!-- run pointcloud_to_laserscan node -->
|
<!-- run pointcloud_to_laserscan node -->
|
||||||
<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan" name="pointcloud_to_laserscan">
|
<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">
|
||||||
|
|
||||||
<param name="use_inf" value="true"/>
|
<param name="use_inf" value="true"/>
|
||||||
<param name="use_concurrency" value="true"/>
|
<param name="use_concurrency" value="true"/>
|
||||||
|
|||||||
@ -10,7 +10,7 @@
|
|||||||
</include>
|
</include>
|
||||||
|
|
||||||
<!-- push pointcloud_to_laserscan nodelet into sensor's nodelet manager-->
|
<!-- push pointcloud_to_laserscan nodelet into sensor's nodelet manager-->
|
||||||
<node pkg="nodelet" type="nodelet" name="pointcloud_to_laserscan" args="load pointcloud_to_laserscan/PointCloudToLaserScanNodelet $(arg camera)_nodelet_manager">
|
<node pkg="nodelet" type="nodelet" name="pointcloud_to_laserscan" args="load pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet $(arg camera)_nodelet_manager">
|
||||||
|
|
||||||
<param name="use_inf" value="true"/>
|
<param name="use_inf" value="true"/>
|
||||||
<param name="use_concurrency" value="true"/>
|
<param name="use_concurrency" value="true"/>
|
||||||
|
|||||||
@ -1,6 +1,6 @@
|
|||||||
<library path="lib/libPointCloudToLaserScanNodelet">
|
<library path="lib/libpointcloud_to_laserscan">
|
||||||
|
|
||||||
<class name="pointcloud_to_laserscan/PointCloudToLaserScanNodelet"
|
<class name="pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet"
|
||||||
type="pointcloud_to_laserscan::PointCloudToLaserScanNodelet"
|
type="pointcloud_to_laserscan::PointCloudToLaserScanNodelet"
|
||||||
base_class_type="nodelet::Nodelet">
|
base_class_type="nodelet::Nodelet">
|
||||||
<description>
|
<description>
|
||||||
|
|||||||
@ -30,5 +30,6 @@
|
|||||||
<run_depend>sensor_msgs</run_depend>
|
<run_depend>sensor_msgs</run_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
|
<nodelet plugin="${prefix}/nodelets.xml"/>
|
||||||
</export>
|
</export>
|
||||||
</package>
|
</package>
|
||||||
@ -38,7 +38,7 @@
|
|||||||
* Author: Paul Bovbel
|
* Author: Paul Bovbel
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <pointcloud_to_laserscan/PointCloudToLaserScanBase.h>
|
#include <pointcloud_to_laserscan/pointcloud_to_laserscan_base.h>
|
||||||
#include <sensor_msgs/LaserScan.h>
|
#include <sensor_msgs/LaserScan.h>
|
||||||
#include <pcl_ros/transforms.h>
|
#include <pcl_ros/transforms.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
@ -39,7 +39,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <pointcloud_to_laserscan/PointCloudToLaserScanBase.h>
|
#include <pointcloud_to_laserscan/pointcloud_to_laserscan_base.h>
|
||||||
|
|
||||||
int main(int argc, char **argv){
|
int main(int argc, char **argv){
|
||||||
ros::init(argc, argv, "pointcloud_to_laserscan");
|
ros::init(argc, argv, "pointcloud_to_laserscan");
|
||||||
|
|||||||
@ -38,7 +38,7 @@
|
|||||||
* Author: Paul Bovbel
|
* Author: Paul Bovbel
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <pointcloud_to_laserscan/PointCloudToLaserScanBase.h>
|
#include <pointcloud_to_laserscan/pointcloud_to_laserscan_base.h>
|
||||||
#include <nodelet/nodelet.h>
|
#include <nodelet/nodelet.h>
|
||||||
|
|
||||||
|
|
||||||
Loading…
x
Reference in New Issue
Block a user