Can launch but not run my Nodelet
Hi everyone,
Since few days I try to understand and use Nodelet to dynamically load process from a cpp Node. I read lots of questions and answer from this forum and I have a problem. (Btw thanks to the community with clear answers on many questions)
I just copied the code from nodelet_tutorial_math and modified it to republish with custom messages and I can launch my Node using this launch file:
<launch>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" />
<node pkg="nodelet" type="nodelet" name="test_nodelet"
args="load test_nodelet/Add nodelet_manager">
</node>
</launch>
But when I try to use the following commands:
rosrun nodelet nodelet manager __name:=nodelet_manager
rosrun nodelet nodelet load test_nodelet/Add nodelet_manager __name:=test_nodelet
I can't run my nodelet because the manager does not find it in the nodelet package:
[ERROR] [1490717511.798024359]: Failed to load nodelet [/nodelet_test] of type [test_nodelet/Add] even after refreshing the cache: According to the loaded plugin descriptions the class test_nodelet/Add with base class type nodelet::Nodelet does not exist. Declared types are depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register image_proc/crop_decimate image_proc/crop_nonZero image_proc/debayer image_proc/rectify image_rotate/image_rotate image_view/disparity image_view/image nodelet_tutorial_math/Plus pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid stereo_image_proc/disparity stereo_image_proc/point_cloud2
[ERROR] [1490717511.798075777]: The error before refreshing the cache was: According to the loaded plugin descriptions the class test_nodelet/Add with base class type nodelet::Nodelet does not exist. Declared types are depth_image_proc/convert_metric depth_image_proc/crop_foremost depth_image_proc/disparity depth_image_proc/point_cloud_xyz depth_image_proc/point_cloud_xyz_radial depth_image_proc/point_cloud_xyzi depth_image_proc/point_cloud_xyzi_radial depth_image_proc/point_cloud_xyzrgb depth_image_proc/register image_proc/crop_decimate image_proc/crop_nonZero image_proc/debayer image_proc/rectify image_rotate/image_rotate image_view/disparity image_view/image nodelet_tutorial_math/Plus pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid stereo_image_proc/disparity stereo_image_proc/point_cloud2
My CMakeList is the following one:
cmake_minimum_required(VERSION 2.8.3)
project(test_nodelet)
add_definitions(-std=c++11)
find_package(catkin REQUIRED COMPONENTS nodelet roscpp std_msgs)
include_directories(${catkin_INCLUDE_DIRS})
catkin_package(
LIBRARIES nodelet_test
CATKIN_DEPENDS nodelet roscpp std_msgs
)
add_library(nodelet_test src/test_nodelet.cpp)
target_link_libraries(nodelet_test ${catkin_LIBRARIES})
if(catkin_EXPORTED_LIBRARIES)
add_dependencies(nodelet_test ${catkin_EXPORTED_LIBRARIES})
endif()
install(TARGETS nodelet_test
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
install(FILES nodelet_test.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
and here is my nodelet_test.xml:
<library path="lib/libnodelet_test">
<class name="test_nodelet/Add"
type="test_nodelet::Add"
base_class_type="nodelet::Nodelet ...