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

Switching between controllers with ros_control / controller_manager

asked 2017-04-11 16:07:49 -0500

updated 2017-04-17 13:08:42 -0500

Is there an easy way to switch between different controllers for a single resource? I would like to control a joint of my Gazebo model either by effort_controllers/JointPositionController or effort_controllers/JointEffortController. I want to switch between these controllers during runtime by pressing a joystick button.

Right now, I make 4 service calls:

  1. Stop the current controller (by calling controller_manager/switch_controller)
  2. Unload the current controller (by calling controller_manager/unload_controller)
  3. Load the new controller (by calling controller_manager/load_controller)
  4. Start the new controller (by calling controller_manager/switch_controller again)

Is there an easier way to do that, like loading both controllers at the same time and only start/stop the corresponding controllers by a single switch_controller call? As the SwitchController Service has parameters for both start_controllers and stop_controllers, this seems to be supported somehow. But if I try to spawn both controllers in a launch file, I get a "resource conflict" error.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2017-04-17 12:52:00 -0500

updated 2017-04-17 13:00:13 -0500

I finally found a way to simplify my approach. If you pass --stopped as an argument to the spawner, you can load a controller without starting it. So I ended up spawning the position controller as usual and the effort controller with the --stopped argument. Now I can switch from one controller to the other by just calling the switch_controller service.

I needed to add the following two lines to my launch file:


<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" ns="/mybot" args="flipper_position_controller"/>

<node name="controller_spawner_stopped" pkg="controller_manager" type="spawner" respawn="false" ns="/mybot" args="--stopped flipper_effort_controller"/>

The code to switch from position controller to effort controller looks like that:


from controller_manager_msgs.srv import SwitchController
...
rospy.wait_for_service('/mybot/controller_manager/switch_controller')
try:
   switch_controller = rospy.ServiceProxy(
                       '/mybot/controller_manager/switch_controller', SwitchController)
   ret = switch_controller(['flipper_effort_controller'], 
                           ['flipper_position_controller'], 2)
   except rospy.ServiceException, e:
      print "Service call failed: %s"%e

edit flag offensive delete link more

Comments

It is still through service call. And I tried cm.unload() function, but return 0(failed) always.

itfanr gravatar image itfanr  ( 2018-09-29 21:02:27 -0500 )edit

When my own controller was switched to another controller effort_controllers/JointTrajectoryController, it was successful, but the robot arm fell down in simulation, does anybody know the reason?

Qt_Yeung gravatar image Qt_Yeung  ( 2020-08-02 15:56:09 -0500 )edit

Did you add multiple hardware interfaces under transmissions for each joint? One for Position based controller and another for Effort based controller?

chiku00 gravatar image chiku00  ( 2022-09-14 15:03:20 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-04-11 16:07:49 -0500

Seen: 3,554 times

Last updated: Apr 17 '17