ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Error when loading MyControllerClass

asked 2011-03-06 19:52:02 -0500

sam gravatar image

updated 2011-03-12 00:52:14 -0500

kwc gravatar image

Hi, I run this tutorial. And everything seems ok, but at last I couldn't load the controller. How to fix that? Thank you~~

It showed that:

 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosparam set MyControllerClass/type MyControllerPlugin
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosparam set MyControllerClass/joint_name r_shoulder_pan_joint
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosrun      pr2_controller_manager pr2_controller_manager load MyControllerClass
 Error when loading MyControllerClass
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$

My controller.h

 #include <pr2_controller_interface/controller.h>
 #include <pr2_mechanism_model/joint.h>

 namespace my_controller_ns{

    class MyControllerClass: public pr2_controller_interface::Controller
    {
        private:
            pr2_mechanism_model::JointState* joint_state_;
            double init_pos_;

        public:
            virtual bool init(pr2_mechanism_model::RobotState *robot,
                    ros::NodeHandle &n);
            virtual void starting();
            virtual void update();
            virtual void stopping();
    };
 }

My controller.cpp

 #include <pluginlib/class_list_macros.h>

 #include "controller.h"

 namespace my_controller_ns {

    /// Controller initialization in non-realtime
    bool MyControllerClass::init(pr2_mechanism_model::RobotState      *robot,ros::NodeHandle &n)
    {
        //使用時會從console取得joint名字才能繼續執行
        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()
    {}
 } // namespace

 /// Register controller to pluginlib
 PLUGINLIB_DECLARE_CLASS(joint_controller_pkg,MyControllerPlugin, 
        my_controller_ns::MyControllerClass, 
        pr2_controller_interface::Controller)

My CMakeLists.txt

 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(joint_controller_lib src/controller.cpp)

My manifest.xml

 <package>
   <description brief="joint_controller">

     joint_controller

   </description>
   <author>sam</author>
   <license>BSD</license>
   <review status="unreviewed" notes=""/>
   <url>http://ros.org/wiki/joint_controller</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>

My controller_plugins.xml

 <library path="lib/libjoint_controller_lib">
   <class name="joint_controller_pkg/MyControllerPlugin"
          type="joint_controller_ns::MyControllerClass"
          base_class_type="pr2_controller_interface::Controller" />
 </library>

I also find some similar error others met and run the instruction

 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ nm lib/libjoint_controller.so | grep pocoBuildManifest
 00002f30 T pocoBuildManifestjoint_controller_pkg__MyControllerPlugin
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$

I also run rxconsole,and it showed that

 Could not load class MyControllerPlugin: According to the loaded plugin descriptions the class MyControllerPlugin with base class type pr2_controller_interface::Controller does not exist ...
(more)
edit retag flag offensive close merge delete

4 Answers

Sort by » oldest newest most voted
1

answered 2011-03-14 13:13:24 -0500

mmwise gravatar image

updated 2011-03-15 06:52:38 -0500

Okay.. I ran through the entire tutorial... and I can reproduce your error when my package path doesn't include the controller.. This is the error

[ERROR] [1300151311.132418409, 151.906000000]: Could not load class MyControllerPlugin: According to the loaded plugin descriptions the class MyControllerPlugin with base class type pr2_controller_interface::Controller does not exist. Declared types are  CartesianTrajectoryController ethercat_trigger_controllers/MultiTriggerController ethercat_trigger_controllers/ProjectorController ethercat_trigger_controllers/TriggerController 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/FakeCalibrationController pr2_calibration_controllers/GripperCalibrationController pr2_calibration_controllers/JointCalibrationController pr2_calibration_controllers/WristCalibrationController pr2_controller_manager/TestController pr2_gripper_sensor_controller/PR2GripperSensorController 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 tff_controller/TFFController
[ERROR] [1300151311.132503256, 151.907000000]: Could not load controller 'my_controller_name' because controller type 'MyControllerPlugin' does not exist

Make sure that you have your path setup correctly in EVERY terminal window. This means you can roscd to the controller package in every terminal. If you don't have your path setup correctly you will get the error.

OR

I can reproduce the error when the controller_plugin.xml does not reflect the actual code as you have in your question. Your namespace is my_controller_ns but you call out in the controller_plugins.xml that the namespace is joint_controller_ns. This is the error

[ERROR] [1300214922.756787931, 74.340000000]: Could not load class my_controller_pkg/MyControllerPlugin: The class my_controller_pkg/MyControllerPlugin could not be loaded. Error: Not found: joint_controller_ns::MyControllerClass
[ERROR] [1300214922.756846627, 74.340000000]: Could not load controller 'my_controller_name' because controller type 'my_controller_pkg/MyControllerPlugin' does not exist

Update your controller_plugin.xml to reflect the actual controller and it should run.

edit flag offensive delete link more

Comments

Thank you for this answer. I have checked that my ~/.bashrc file:"... source /opt/ros/cturtle/setup.bash export ROS_PACKAGE_PATH=/home/sam/code/ros/control/joint_controller_pkg:/opt/ros/cturtle/stacks;", and I can roscd to that package in any terminal,but also can't load controller type...
sam gravatar image sam  ( 2011-03-15 01:04:34 -0500 )edit
okay is the controller in the list when you do rosrun pr2_controller_manager pr2_controller_manager list-types
mmwise gravatar image mmwise  ( 2011-03-15 06:44:08 -0500 )edit
I see a problem ... controller_plugins.xml does not match your controller... your namespace is my_controller_ns yet you have joint_controller_ns called out in your controller_plugins.xml
mmwise gravatar image mmwise  ( 2011-03-15 06:47:32 -0500 )edit
The namespace mismatch returns the same error...
mmwise gravatar image mmwise  ( 2011-03-15 06:49:18 -0500 )edit
So...have you succeeded to load that controller??
sam gravatar image sam  ( 2011-03-16 03:38:38 -0500 )edit
Yes I loaded the controller for the tutorial in gazebo .. i posted the fix in the above answer as well.. have you had any success?
mmwise gravatar image mmwise  ( 2011-03-16 06:07:05 -0500 )edit
1

answered 2011-03-11 01:36:08 -0500

Guido gravatar image

updated 2011-03-13 21:34:33 -0500

Hi Sam,

According to a thread on ros-users: http://ros-users.122217.n3.nabble.com/Registering-controller-on-PR2-td1872398.html#a1873107), custom controllers are not automatically loaded when bringing up the robot. For pr2 users, you must use "roslaunch /etc/ros/robot.launch" instead of "robot start". There must be some instruction to collect custom controllers.

Wish you luck,

Guido

edit flag offensive delete link more

Comments

Thank you for this information. I have confused that what is the relation of loading a custom controller and run roslaunch /etc/ros/robot.launch ? and what is robot start command? Should I also use "rosrun pr2_controller_manager pr2_controller_manager load MyControllerClass" ?
sam gravatar image sam  ( 2011-03-11 03:33:48 -0500 )edit
are the controllers in your ROS_PACKAGE_PATH?
mmwise gravatar image mmwise  ( 2011-03-11 06:45:21 -0500 )edit
Yes,I have run "export ROS_PACKAGE_PATH=$PWD:$ROS_PACKAGE_PATH;" in my controller package directory.
sam gravatar image sam  ( 2011-03-11 16:05:29 -0500 )edit
does the plugin description show up when you run..... rospack plugins --attrib=plugin pr2_controller_interface
mmwise gravatar image mmwise  ( 2011-03-11 17:15:15 -0500 )edit
Yes,it really showed up,I edit my origin post to show the result~ I also edit the origin running command at the first post ( add parameters). I also find one small bug that cmake lib name incorrect,but after I revised the origin problem still there.
sam gravatar image sam  ( 2011-03-11 21:41:31 -0500 )edit
did you put the controller configuration on the parameter server? http://www.ros.org/wiki/pr2_controller_manager/Troubleshooting
mmwise gravatar image mmwise  ( 2011-03-12 12:19:02 -0500 )edit
Yes,I have revised first post before.The command is : "rosparam set MyControllerClass/type MyControllerPlugin rosparam set MyControllerClass/joint_name r_shoulder_pan_joint pr2_controller_manager pr2_controller_manager load MyControllerClass" But I don't know my controller name is correct or not.
sam gravatar image sam  ( 2011-03-12 14:03:58 -0500 )edit
okay I haven't given up on you... I'm going to try the tutorial out on monday and figure it out!
mmwise gravatar image mmwise  ( 2011-03-13 18:38:36 -0500 )edit
0

answered 2011-03-19 00:31:04 -0500

sam gravatar image

I tested that I can run that controller with warning...

 rosrun pr2_controller_manager pr2_controller_manager start MyControllerClass

But I found one doc bug?

 double desired_pos = init_pos_ + 0.5 * sin(ros::Time::now().toSec());

When I change 0.5 to 30, pr2 will move smoothly on sine wave like webpage says. But if I use 0.5 it just move very little.

edit flag offensive delete link more
0

answered 2011-03-17 02:38:47 -0500

sam gravatar image

updated 2011-03-17 03:49:23 -0500

Wow~~Great success!! Thank all of you very much~~~

Let me summarized my error:

First, I don't know I should run echo "export ROS_PACKAGE_PATH=$PWD:$ROS_PACKAGE_PATH;" >> ~/.bashrc so I just run this command for temporially can be make by rosmake: export ROS_PACKAGE_PATH=$PWD:$ROS_PACKAGE_PATH;

Second, When I change my project name,I also change the controller_plugins.xml file's type. That I shouldn't change, but I couldn't find it, so I continue to try to change namespace or pluginname or something...

Now it's works~~ Thank you again~~

My screen shows:

 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosparam set MyControllerClass/type MyControllerPlugin
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosparam set MyControllerClass/joint_name r_shoulder_pan_joint
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$ rosrun pr2_controller_manager pr2_controller_manager load MyControllerClass
 Loaded MyControllerClass
 sam@sam-desktop:~/code/ros/controller/joint_controller_pkg$

Next terminal:

 [INFO] 1300372190.324458: Started controllers: base_controller, base_odometry, head_traj_controller, laser_tilt_controller, torso_controller, r_gripper_controller, l_gripper_controller, r_arm_controller, l_arm_controller
 [ INFO] [1300372190.359610589, 0.596000000]: Initializing Odom sensor
 [ INFO] [1300372190.400242444, 0.641000000]: Odom sensor activated
 [ INFO] [1300372190.450955336, 0.685000000]: Kalman filter initialized with odom measurement
 [ WARN] [1300372211.880481727, 21.544000000]: The deprecated controller type MyControllerPlugin was not found.  Using the namespaced version joint_controller_pkg/MyControllerPlugin instead.  Please update your configuration to use the namespaced version.

The last question is that there appear one warning,is that correct for controllers?

edit flag offensive delete link more

Comments

I've never seen that warning I'll look into it on monday...
mmwise gravatar image mmwise  ( 2011-03-18 20:25:09 -0500 )edit

Hi, appending package name in front of MyControllerPlugin, while loading into the rosparam will make this warning go away.

aknirala gravatar image aknirala  ( 2012-06-22 09:42:18 -0500 )edit

Question Tools

Stats

Asked: 2011-03-06 19:52:02 -0500

Seen: 2,396 times

Last updated: Mar 19 '11