PLUGINLIB_REGISTER_CLASS is deprecated, but should still work just fine.<br><br>I wonder if the line: "using namespace my_controller_ns" before the macro could screw things up. I don't have a great reason for this, but I seem to remember the Poco manifest stuff being a bit finiky when it was called from within a namespace and this could have a similar effect. Perhaps, instead of using the namespace, remove that line, call the macro, open the my_controller_ns namespace, and put the rest of your implementation inside of that. I'm not sure that'll fix anything, but its worth a shot and its more consistent with how most of our plugins are written.<br>
<br>Hope this helps,<br><br>Eitan<br><br><div class="gmail_quote">On Tue, Aug 3, 2010 at 1:51 PM, Stuart Glaser <span dir="ltr"><<a href="mailto:sglaser@willowgarage.com">sglaser@willowgarage.com</a>></span> wrote:<br>
<blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">He does have PLUGINLIB_REGISTER_CLASS.  Doesn't that still work?<br>
<br>
-Stu<br>
<div><div></div><div class="h5"><br>
On Tue, Aug 3, 2010 at 1:28 PM, Tully Foote <<a href="mailto:tfoote@willowgarage.com">tfoote@willowgarage.com</a>> wrote:<br>
> That error is due to a lack of the PLUGINLIB_DECLARE_CLASS macro.<br>
>  See <a href="http://www.ros.org/wiki/pluginlib/Troubleshooting" target="_blank">http://www.ros.org/wiki/pluginlib/Troubleshooting</a><br>
><br>
> Tully<br>
> On Tue, Aug 3, 2010 at 11:59 AM, Stuart Glaser <<a href="mailto:sglaser@willowgarage.com">sglaser@willowgarage.com</a>><br>
> wrote:<br>
>><br>
>> Hi Koen,<br>
>><br>
>> This error:<br>
>><br>
>> Cannot load library: No manifest in<br>
>><br>
>> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so:<br>
>> MyControllerPlugin"<br>
>><br>
>> indicates that the library was built incorrectly.  Pluginlib searches<br>
>> the library for a particular symbol in order to find the plugins, and<br>
>> this error explains that it couldn't find the symbol.  Run the<br>
>> following to see what plugins the library contains:<br>
>><br>
>> nm lib/libmy_controller_lib.so  | grep pocoBuildManifest<br>
>><br>
>> Is your plugin listed?<br>
>><br>
>> -Stu<br>
>><br>
>> On Tue, Aug 3, 2010 at 11:02 AM, koen buys <<a href="mailto:koen.buys@mech.kuleuven.be">koen.buys@mech.kuleuven.be</a>><br>
>> wrote:<br>
>> > $ cat controller_plugins.xml<br>
>> > <library path="lib/libmy_controller_lib"><br>
>> >  <class name="MyControllerPlugin"<br>
>> >         type="my_controller_ns::MyControllerClass"<br>
>> >         base_class_type="pr2_controller_interface::Controller" /><br>
>> > </library><br>
>> ><br>
>> ><br>
>> > On 3 August 2010 18:44, Rob Wheeler <<a href="mailto:wheeler@willowgarage.com">wheeler@willowgarage.com</a>> wrote:<br>
>> >> What does your controller_plugins.xml file look like?<br>
>> >><br>
>> >> -R<br>
>> >><br>
>> >> On Tue, Aug 3, 2010 at 7:23 AM, koen buys <<a href="mailto:koen.buys@mech.kuleuven.be">koen.buys@mech.kuleuven.be</a>><br>
>> >> wrote:<br>
>> >>><br>
>> >>> Hi all,<br>
>> >>><br>
>> >>> I'm trying to run the following tutorial:<br>
>> >>><br>
>> >>><br>
>> >>> <a href="http://www.ros.org/wiki/pr2_mechanism/Tutorials/Running%20a%20realtime%20joint%20controller" target="_blank">http://www.ros.org/wiki/pr2_mechanism/Tutorials/Running%20a%20realtime%20joint%20controller</a><br>

>> >>> Rxconsole is giving me the following error:<br>
>> >>><br>
>> >>> "Could not load class MyControllerPlugin: Failed to load library<br>
>> >>><br>
>> >>><br>
>> >>> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so.<br>
>> >>> Make sure that you are calling the PLUGINLIB_REGISTER_CLASS macro in<br>
>> >>> the library code, and that names are consistent between this macro and<br>
>> >>> your XML. Error string: Cannot load library: No manifest in<br>
>> >>><br>
>> >>><br>
>> >>> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so:<br>
>> >>> MyControllerPlugin"<br>
>> >>><br>
>> >>> Together with the following error after:<br>
>> >>><br>
>> >>> "Could not load controller 'my_controller_name' because controller<br>
>> >>> type 'MyControllerPlugin' does not exist"<br>
>> >>><br>
>> >>> We couldn't find the cause of it. When I did a :<br>
>> >>><br>
>> >>> $ rosrun pr2_controller_manager pr2_controller_manager list-types<br>
>> >>> CartesianTrajectoryController<br>
>> >>> ContactObserverPlugin<br>
>> >>> JTTeleopController<br>
>> >>> JointGravityController<br>
>> >>> JointPendulumController<br>
>> >>> MyControllerPlugin<br>
>> >>> SlipGripControllerPlugin<br>
>> >>> SrhFakeJointCalibrationController<br>
>> >>> StanfordWBCPump<br>
>> >>> VelController<br>
>> >>> ethercat_trigger_controllers/MultiTriggerController<br>
>> >>> ethercat_trigger_controllers/ProjectorController<br>
>> >>> ethercat_trigger_controllers/TriggerController<br>
>> >>> ft_eval/PoseForceController<br>
>> >>> ft_eval/TwistForceController<br>
>> >>> joint_qualification_controllers/CheckoutController<br>
>> >>> joint_qualification_controllers/CounterbalanceTestController<br>
>> >>> joint_qualification_controllers/HeadPositionController<br>
>> >>> joint_qualification_controllers/HysteresisController<br>
>> >>> joint_qualification_controllers/JointLimitCalibrationController<br>
>> >>> joint_qualification_controllers/MotorJointCalibrationController<br>
>> >>> joint_qualification_controllers/WristDifferenceController<br>
>> >>> pr2_calibration_controllers/CasterCalibrationController<br>
>> >>> pr2_calibration_controllers/GripperCalibrationController<br>
>> >>> pr2_calibration_controllers/JointCalibrationController<br>
>> >>> pr2_calibration_controllers/WristCalibrationController<br>
>> >>> pr2_controller_manager/TestController<br>
>> >>> pr2_mechanism_controllers/CasterController<br>
>> >>> pr2_mechanism_controllers/CasterControllerNode<br>
>> >>> pr2_mechanism_controllers/LaserScannerTrajController<br>
>> >>> pr2_mechanism_controllers/Pr2BaseController<br>
>> >>> pr2_mechanism_controllers/Pr2BaseController2<br>
>> >>> pr2_mechanism_controllers/Pr2GripperController<br>
>> >>> pr2_mechanism_controllers/Pr2Odometry<br>
>> >>> robot_mechanism_controllers/CartesianPoseController<br>
>> >>> robot_mechanism_controllers/CartesianTwistController<br>
>> >>> robot_mechanism_controllers/CartesianWrenchController<br>
>> >>> robot_mechanism_controllers/JointEffortController<br>
>> >>> robot_mechanism_controllers/JointPositionController<br>
>> >>> robot_mechanism_controllers/JointSplineTrajectoryController<br>
>> >>> robot_mechanism_controllers/JointTrajectoryActionController<br>
>> >>> robot_mechanism_controllers/JointVelocityController<br>
>> >>> rttuning_controllers/JointTuningController<br>
>> >>> teleop_controllers/JinvTeleopController7<br>
>> >>> tff_controller/TFFController<br>
>> >>> tirt/TirtController<br>
>> >>><br>
>> >>> It shows up. However now:<br>
>> >>><br>
>> >>> $ rosrun pr2_controller_manager pr2_controller_manager load<br>
>> >>> MyControllerPlugin<br>
>> >>> Error when loading MyControllerPlugin<br>
>> >>><br>
>> >>> This is my manifest:<br>
>> >>><br>
>> >>> <package><br>
>> >>>  <description brief="my_controller_pkg"><br>
>> >>><br>
>> >>>     my_controller_pkg<br>
>> >>><br>
>> >>>  </description><br>
>> >>>  <author>Koen</author><br>
>> >>>  <license>BSD</license><br>
>> >>>  <review status="unreviewed" notes=""/><br>
>> >>>  <url><a href="http://ros.org/wiki/my_controller_pkg" target="_blank">http://ros.org/wiki/my_controller_pkg</a></url><br>
>> >>>  <depend package="pr2_controller_interface"/><br>
>> >>>  <depend package="pr2_mechanism_model"/><br>
>> >>>  <depend package="pluginlib"/><br>
>> >>>  <export><br>
>> >>>    <pr2_controller_interface plugin="${prefix}/controller_plugins.xml"<br>
>> >>> /><br>
>> >>>  </export><br>
>> >>> </package><br>
>> >>><br>
>> >>> This is my CMakeLists:<br>
>> >>><br>
>> >>> cmake_minimum_required(VERSION 2.4.6)<br>
>> >>> include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)<br>
>> >>><br>
>> >>> # Set the build type.  Options are:<br>
>> >>> #  Coverage       : w/ debug symbols, w/o optimization, w/<br>
>> >>> code-coverage<br>
>> >>> #  Debug          : w/ debug symbols, w/o optimization<br>
>> >>> #  Release        : w/o debug symbols, w/ optimization<br>
>> >>> #  RelWithDebInfo : w/ debug symbols, w/ optimization<br>
>> >>> #  MinSizeRel     : w/o debug symbols, w/ optimization, stripped<br>
>> >>> binaries<br>
>> >>> #set(ROS_BUILD_TYPE RelWithDebInfo)<br>
>> >>><br>
>> >>> rosbuild_init()<br>
>> >>><br>
>> >>> #set the default path for built executables to the "bin" directory<br>
>> >>> set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)<br>
>> >>> #set the default path for built libraries to the "lib" directory<br>
>> >>> set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)<br>
>> >>><br>
>> >>> #uncomment if you have defined messages<br>
>> >>> #rosbuild_genmsg()<br>
>> >>> #uncomment if you have defined services<br>
>> >>> #rosbuild_gensrv()<br>
>> >>><br>
>> >>> #common commands for building c++ executables and libraries<br>
>> >>> #rosbuild_add_library(${PROJECT_NAME} src/example.cpp)<br>
>> >>> #target_link_libraries(${PROJECT_NAME} another_library)<br>
>> >>> #rosbuild_add_boost_directories()<br>
>> >>> #rosbuild_link_boost(${PROJECT_NAME} thread)<br>
>> >>> #rosbuild_add_executable(example examples/example.cpp)<br>
>> >>> #target_link_libraries(example ${PROJECT_NAME})<br>
>> >>> rosbuild_add_library(my_controller_lib src/my_controller_file.cpp)<br>
>> >>><br>
>> >>> And this is the content of my source file:<br>
>> >>><br>
>> >>> #include "my_controller_pkg/my_controller_file.h"<br>
>> >>> #include <pluginlib/class_list_macros.h><br>
>> >>><br>
>> >>> using namespace my_controller_ns;<br>
>> >>><br>
>> >>> /// Register controller to pluginlib<br>
>> >>> PLUGINLIB_REGISTER_CLASS(MyControllerPlugin,<br>
>> >>>                         my_controller_ns::MyControllerClass,<br>
>> >>>                         pr2_controller_interface::Controller)<br>
>> >>><br>
>> >>> /// Controller initialization in non-realtime<br>
>> >>> bool MyControllerClass::init(pr2_mechanism_model::RobotState *robot,<br>
>> >>>                            ros::NodeHandle &n)<br>
>> >>> {<br>
>> >>>  std::string joint_name;<br>
>> >>>  if (!n.getParam("joint_name", joint_name))<br>
>> >>>  {<br>
>> >>>    ROS_ERROR("No joint given in namespace: '%s')",<br>
>> >>>              n.getNamespace().c_str());<br>
>> >>>    return false;<br>
>> >>>  }<br>
>> >>><br>
>> >>>  joint_state_ = robot->getJointState(joint_name);<br>
>> >>>  if (!joint_state_)<br>
>> >>>  {<br>
>> >>>    ROS_ERROR("MyController could not find joint named '%s'",<br>
>> >>>              joint_name.c_str());<br>
>> >>>    return false;<br>
>> >>>  }<br>
>> >>>  return true;<br>
>> >>> }<br>
>> >>><br>
>> >>><br>
>> >>> /// Controller startup in realtime<br>
>> >>> void MyControllerClass::starting()<br>
>> >>> {<br>
>> >>>  init_pos_ = joint_state_->position_;<br>
>> >>> }<br>
>> >>><br>
>> >>><br>
>> >>> /// Controller update loop in realtime<br>
>> >>> void MyControllerClass::update()<br>
>> >>> {<br>
>> >>>  double desired_pos = init_pos_ + 0.5 * sin(ros::Time::now().toSec());<br>
>> >>>  double current_pos = joint_state_->position_;<br>
>> >>>  joint_state_->commanded_effort_ = -10 * (current_pos - desired_pos);<br>
>> >>> }<br>
>> >>><br>
>> >>><br>
>> >>> /// Controller stopping in realtime<br>
>> >>> void MyControllerClass::stopping()<br>
>> >>> {}<br>
>> >>> _______________________________________________<br>
>> >>> ros-users mailing list<br>
>> >>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>> >>> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
>> >><br>
>> >><br>
>> > _______________________________________________<br>
>> > ros-users mailing list<br>
>> > <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>> > <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
>> ><br>
>><br>
>><br>
>><br>
>> --<br>
>> Stuart Glaser<br>
>> sglaser -at- willowgarage -dot- com<br>
>> <a href="http://www.willowgarage.com" target="_blank">www.willowgarage.com</a><br>
>> _______________________________________________<br>
>> ros-users mailing list<br>
>> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
>> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
><br>
><br>
><br>
> --<br>
> Tully Foote<br>
> Systems Engineer<br>
> Willow Garage, Inc.<br>
> <a href="mailto:tfoote@willowgarage.com">tfoote@willowgarage.com</a><br>
> (650) 475-2827<br>
><br>
> _______________________________________________<br>
> ros-users mailing list<br>
> <a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
> <a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
><br>
><br>
<br>
<br>
<br>
--<br>
Stuart Glaser<br>
sglaser -at- willowgarage -dot- com<br>
<a href="http://www.willowgarage.com" target="_blank">www.willowgarage.com</a><br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</div></div></blockquote></div><br>