[ros-users] Running a realtime joint controller: Tutorial Error

koen buys koen.buys at mech.kuleuven.be
Wed Aug 4 06:44:35 UTC 2010


Hi Eitan,

This was indeed the solution.

Koen

On 3 August 2010 23:50, Eitan Marder-Eppstein <eitan at willowgarage.com> wrote:
> PLUGINLIB_REGISTER_CLASS is deprecated, but should still work just fine.
>
> 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.
>
> Hope this helps,
>
> Eitan
>
> On Tue, Aug 3, 2010 at 1:51 PM, Stuart Glaser <sglaser at willowgarage.com>
> wrote:
>>
>> He does have PLUGINLIB_REGISTER_CLASS.  Doesn't that still work?
>>
>> -Stu
>>
>> On Tue, Aug 3, 2010 at 1:28 PM, Tully Foote <tfoote at willowgarage.com>
>> wrote:
>> > That error is due to a lack of the PLUGINLIB_DECLARE_CLASS macro.
>> >  See http://www.ros.org/wiki/pluginlib/Troubleshooting
>> >
>> > Tully
>> > On Tue, Aug 3, 2010 at 11:59 AM, Stuart Glaser
>> > <sglaser at willowgarage.com>
>> > wrote:
>> >>
>> >> Hi Koen,
>> >>
>> >> This error:
>> >>
>> >> Cannot load library: No manifest in
>> >>
>> >>
>> >> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so:
>> >> MyControllerPlugin"
>> >>
>> >> indicates that the library was built incorrectly.  Pluginlib searches
>> >> the library for a particular symbol in order to find the plugins, and
>> >> this error explains that it couldn't find the symbol.  Run the
>> >> following to see what plugins the library contains:
>> >>
>> >> nm lib/libmy_controller_lib.so  | grep pocoBuildManifest
>> >>
>> >> Is your plugin listed?
>> >>
>> >> -Stu
>> >>
>> >> On Tue, Aug 3, 2010 at 11:02 AM, koen buys <koen.buys at mech.kuleuven.be>
>> >> wrote:
>> >> > $ cat controller_plugins.xml
>> >> > <library path="lib/libmy_controller_lib">
>> >> >  <class name="MyControllerPlugin"
>> >> >         type="my_controller_ns::MyControllerClass"
>> >> >         base_class_type="pr2_controller_interface::Controller" />
>> >> > </library>
>> >> >
>> >> >
>> >> > On 3 August 2010 18:44, Rob Wheeler <wheeler at willowgarage.com> wrote:
>> >> >> What does your controller_plugins.xml file look like?
>> >> >>
>> >> >> -R
>> >> >>
>> >> >> On Tue, Aug 3, 2010 at 7:23 AM, koen buys
>> >> >> <koen.buys at mech.kuleuven.be>
>> >> >> wrote:
>> >> >>>
>> >> >>> Hi all,
>> >> >>>
>> >> >>> I'm trying to run the following tutorial:
>> >> >>>
>> >> >>>
>> >> >>>
>> >> >>> http://www.ros.org/wiki/pr2_mechanism/Tutorials/Running%20a%20realtime%20joint%20controller
>> >> >>> Rxconsole is giving me the following error:
>> >> >>>
>> >> >>> "Could not load class MyControllerPlugin: Failed to load library
>> >> >>>
>> >> >>>
>> >> >>>
>> >> >>> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so.
>> >> >>> Make sure that you are calling the PLUGINLIB_REGISTER_CLASS macro
>> >> >>> in
>> >> >>> the library code, and that names are consistent between this macro
>> >> >>> and
>> >> >>> your XML. Error string: Cannot load library: No manifest in
>> >> >>>
>> >> >>>
>> >> >>>
>> >> >>> /home/kbuys/ros/private-kul-ros-pkg/ros_controller_tutorials/my_controller_pkg/lib/libmy_controller_lib.so:
>> >> >>> MyControllerPlugin"
>> >> >>>
>> >> >>> Together with the following error after:
>> >> >>>
>> >> >>> "Could not load controller 'my_controller_name' because controller
>> >> >>> type 'MyControllerPlugin' does not exist"
>> >> >>>
>> >> >>> We couldn't find the cause of it. When I did a :
>> >> >>>
>> >> >>> $ rosrun pr2_controller_manager pr2_controller_manager list-types
>> >> >>> CartesianTrajectoryController
>> >> >>> ContactObserverPlugin
>> >> >>> JTTeleopController
>> >> >>> JointGravityController
>> >> >>> JointPendulumController
>> >> >>> MyControllerPlugin
>> >> >>> SlipGripControllerPlugin
>> >> >>> SrhFakeJointCalibrationController
>> >> >>> StanfordWBCPump
>> >> >>> VelController
>> >> >>> ethercat_trigger_controllers/MultiTriggerController
>> >> >>> ethercat_trigger_controllers/ProjectorController
>> >> >>> ethercat_trigger_controllers/TriggerController
>> >> >>> ft_eval/PoseForceController
>> >> >>> ft_eval/TwistForceController
>> >> >>> joint_qualification_controllers/CheckoutController
>> >> >>> joint_qualification_controllers/CounterbalanceTestController
>> >> >>> joint_qualification_controllers/HeadPositionController
>> >> >>> joint_qualification_controllers/HysteresisController
>> >> >>> joint_qualification_controllers/JointLimitCalibrationController
>> >> >>> joint_qualification_controllers/MotorJointCalibrationController
>> >> >>> joint_qualification_controllers/WristDifferenceController
>> >> >>> pr2_calibration_controllers/CasterCalibrationController
>> >> >>> pr2_calibration_controllers/GripperCalibrationController
>> >> >>> pr2_calibration_controllers/JointCalibrationController
>> >> >>> pr2_calibration_controllers/WristCalibrationController
>> >> >>> pr2_controller_manager/TestController
>> >> >>> pr2_mechanism_controllers/CasterController
>> >> >>> pr2_mechanism_controllers/CasterControllerNode
>> >> >>> pr2_mechanism_controllers/LaserScannerTrajController
>> >> >>> pr2_mechanism_controllers/Pr2BaseController
>> >> >>> pr2_mechanism_controllers/Pr2BaseController2
>> >> >>> pr2_mechanism_controllers/Pr2GripperController
>> >> >>> pr2_mechanism_controllers/Pr2Odometry
>> >> >>> robot_mechanism_controllers/CartesianPoseController
>> >> >>> robot_mechanism_controllers/CartesianTwistController
>> >> >>> robot_mechanism_controllers/CartesianWrenchController
>> >> >>> robot_mechanism_controllers/JointEffortController
>> >> >>> robot_mechanism_controllers/JointPositionController
>> >> >>> robot_mechanism_controllers/JointSplineTrajectoryController
>> >> >>> robot_mechanism_controllers/JointTrajectoryActionController
>> >> >>> robot_mechanism_controllers/JointVelocityController
>> >> >>> rttuning_controllers/JointTuningController
>> >> >>> teleop_controllers/JinvTeleopController7
>> >> >>> tff_controller/TFFController
>> >> >>> tirt/TirtController
>> >> >>>
>> >> >>> It shows up. However now:
>> >> >>>
>> >> >>> $ rosrun pr2_controller_manager pr2_controller_manager load
>> >> >>> MyControllerPlugin
>> >> >>> Error when loading MyControllerPlugin
>> >> >>>
>> >> >>> This is my manifest:
>> >> >>>
>> >> >>> <package>
>> >> >>>  <description brief="my_controller_pkg">
>> >> >>>
>> >> >>>     my_controller_pkg
>> >> >>>
>> >> >>>  </description>
>> >> >>>  <author>Koen</author>
>> >> >>>  <license>BSD</license>
>> >> >>>  <review status="unreviewed" notes=""/>
>> >> >>>  <url>http://ros.org/wiki/my_controller_pkg</url>
>> >> >>>  <depend package="pr2_controller_interface"/>
>> >> >>>  <depend package="pr2_mechanism_model"/>
>> >> >>>  <depend package="pluginlib"/>
>> >> >>>  <export>
>> >> >>>    <pr2_controller_interface
>> >> >>> plugin="${prefix}/controller_plugins.xml"
>> >> >>> />
>> >> >>>  </export>
>> >> >>> </package>
>> >> >>>
>> >> >>> This is my CMakeLists:
>> >> >>>
>> >> >>> cmake_minimum_required(VERSION 2.4.6)
>> >> >>> include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
>> >> >>>
>> >> >>> # Set the build type.  Options are:
>> >> >>> #  Coverage       : w/ debug symbols, w/o optimization, w/
>> >> >>> code-coverage
>> >> >>> #  Debug          : w/ debug symbols, w/o optimization
>> >> >>> #  Release        : w/o debug symbols, w/ optimization
>> >> >>> #  RelWithDebInfo : w/ debug symbols, w/ optimization
>> >> >>> #  MinSizeRel     : w/o debug symbols, w/ optimization, stripped
>> >> >>> binaries
>> >> >>> #set(ROS_BUILD_TYPE RelWithDebInfo)
>> >> >>>
>> >> >>> rosbuild_init()
>> >> >>>
>> >> >>> #set the default path for built executables to the "bin" directory
>> >> >>> set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
>> >> >>> #set the default path for built libraries to the "lib" directory
>> >> >>> set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
>> >> >>>
>> >> >>> #uncomment if you have defined messages
>> >> >>> #rosbuild_genmsg()
>> >> >>> #uncomment if you have defined services
>> >> >>> #rosbuild_gensrv()
>> >> >>>
>> >> >>> #common commands for building c++ executables and libraries
>> >> >>> #rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
>> >> >>> #target_link_libraries(${PROJECT_NAME} another_library)
>> >> >>> #rosbuild_add_boost_directories()
>> >> >>> #rosbuild_link_boost(${PROJECT_NAME} thread)
>> >> >>> #rosbuild_add_executable(example examples/example.cpp)
>> >> >>> #target_link_libraries(example ${PROJECT_NAME})
>> >> >>> rosbuild_add_library(my_controller_lib src/my_controller_file.cpp)
>> >> >>>
>> >> >>> And this is the content of my source file:
>> >> >>>
>> >> >>> #include "my_controller_pkg/my_controller_file.h"
>> >> >>> #include <pluginlib/class_list_macros.h>
>> >> >>>
>> >> >>> using namespace my_controller_ns;
>> >> >>>
>> >> >>> /// Register controller to pluginlib
>> >> >>> PLUGINLIB_REGISTER_CLASS(MyControllerPlugin,
>> >> >>>                         my_controller_ns::MyControllerClass,
>> >> >>>                         pr2_controller_interface::Controller)
>> >> >>>
>> >> >>> /// Controller initialization in non-realtime
>> >> >>> bool MyControllerClass::init(pr2_mechanism_model::RobotState
>> >> >>> *robot,
>> >> >>>                            ros::NodeHandle &n)
>> >> >>> {
>> >> >>>  std::string joint_name;
>> >> >>>  if (!n.getParam("joint_name", joint_name))
>> >> >>>  {
>> >> >>>    ROS_ERROR("No joint given in namespace: '%s')",
>> >> >>>              n.getNamespace().c_str());
>> >> >>>    return false;
>> >> >>>  }
>> >> >>>
>> >> >>>  joint_state_ = robot->getJointState(joint_name);
>> >> >>>  if (!joint_state_)
>> >> >>>  {
>> >> >>>    ROS_ERROR("MyController could not find joint named '%s'",
>> >> >>>              joint_name.c_str());
>> >> >>>    return false;
>> >> >>>  }
>> >> >>>  return true;
>> >> >>> }
>> >> >>>
>> >> >>>
>> >> >>> /// Controller startup in realtime
>> >> >>> void MyControllerClass::starting()
>> >> >>> {
>> >> >>>  init_pos_ = joint_state_->position_;
>> >> >>> }
>> >> >>>
>> >> >>>
>> >> >>> /// Controller update loop in realtime
>> >> >>> void MyControllerClass::update()
>> >> >>> {
>> >> >>>  double desired_pos = init_pos_ + 0.5 *
>> >> >>> sin(ros::Time::now().toSec());
>> >> >>>  double current_pos = joint_state_->position_;
>> >> >>>  joint_state_->commanded_effort_ = -10 * (current_pos -
>> >> >>> desired_pos);
>> >> >>> }
>> >> >>>
>> >> >>>
>> >> >>> /// Controller stopping in realtime
>> >> >>> void MyControllerClass::stopping()
>> >> >>> {}
>> >> >>> _______________________________________________
>> >> >>> ros-users mailing list
>> >> >>> ros-users at code.ros.org
>> >> >>> https://code.ros.org/mailman/listinfo/ros-users
>> >> >>
>> >> >>
>> >> > _______________________________________________
>> >> > ros-users mailing list
>> >> > ros-users at code.ros.org
>> >> > https://code.ros.org/mailman/listinfo/ros-users
>> >> >
>> >>
>> >>
>> >>
>> >> --
>> >> Stuart Glaser
>> >> sglaser -at- willowgarage -dot- com
>> >> www.willowgarage.com
>> >> _______________________________________________
>> >> ros-users mailing list
>> >> ros-users at code.ros.org
>> >> https://code.ros.org/mailman/listinfo/ros-users
>> >
>> >
>> >
>> > --
>> > Tully Foote
>> > Systems Engineer
>> > Willow Garage, Inc.
>> > tfoote at willowgarage.com
>> > (650) 475-2827
>> >
>> > _______________________________________________
>> > ros-users mailing list
>> > ros-users at code.ros.org
>> > https://code.ros.org/mailman/listinfo/ros-users
>> >
>> >
>>
>>
>>
>> --
>> Stuart Glaser
>> sglaser -at- willowgarage -dot- com
>> www.willowgarage.com
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>
>



More information about the ros-users mailing list