0
$\begingroup$

Rosanswers logo

I'm using the abb_robot_driver package to control YuMi IRB 14000, and I want to switch the controller from inside the python script, and not the terminal, to do so I have tried the following solution which didn't work, and I don't know why!

import rospy    
import time
from controller_manager_msgs.srv import *

rospy.wait_for_service("/yumi/rws/sm_addin/stop_egm")
rospy.wait_for_service("/yumi/rws/sm_addin/start_egm_joint")
rospy.wait_for_service("/yumi/egm/controller_manager/switch_controller")

stop_egm = rospy.ServiceProxy("/yumi/rws/sm_addin/stop_egm", TriggerWithResultCode)
start_egm = rospy.ServiceProxy("/yumi/rws/sm_addin/start_egm_joint", TriggerWithResultCode)
switch_controller = rospy.ServiceProxy("/yumi/egm/controller_manager/switch_controller", SwitchController)

stop_egm()
time.sleep(1)

if arm == LEFT:
    cur_arm = group_l
    controller_name="left_arm_controller"
elif arm == RIGHT:
    cur_arm = group_r
    controller_name="right_arm_controller"
elif arm == BOTH:
    cur_arm = group_both
    controller_name="both_arms_controller"
start_egm()
 time.sleep(1)
switch_controller(start_controllers=controller_name, stop_controllers="", strictness=1, start_asap=False, timeout=0.0)

Turns that switching the controller by calling the service this way didn't work, thus I tried this brute force way:

controller_conf = "start_controllers: [{}] \nstop_controllers: [''] \nstrictness: 1 \nstart_asap: false \ntimeout: 0.0".format(controller_name)
import subprocess
subprocess.run(["rosservice", "call", "/yumi/egm/controller_manager/switch_controller", controller_conf]) 

can you please tell me why the first approach didn't work, and how can I solve it? thanks in advance


Originally posted by bhomaidan on ROS Answers with karma: 114 on 2021-12-01

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Both start_controllers and stop_controllers are supposed to be list[str] (from here):

# The SwitchController service allows you stop a number of controllers
# and start a number of controllers, all in one single timestep of the
# controller_manager control loop.
# To switch controllers, specify
#  * the list of controller names to start,
#  * the list of controller names to stop, and
#  * the strictness (BEST_EFFORT or STRICT)
#    * STRICT means that switching will fail if anything goes wrong (an invalid
#      controller name, a controller that failed to start, etc. )
#    * BEST_EFFORT means that even when something goes wrong with on controller,
#      the service will still try to start/stop the remaining controllers
#  * start the controllers as soon as their hardware dependencies are ready, will
#    wait for all interfaces to be ready otherwise
#  * the timeout in seconds before aborting pending controllers. Zero for infinite
# The return value "ok" indicates if the controllers were switched
# successfully or not.  The meaning of success depends on the
# specified strictness.
string[] start_controllers
string[] stop_controllers
int32 strictness
int32 BEST_EFFORT=1
int32 STRICT=2
bool start_asap
float64 timeout
---
bool ok

You're passing plain strs.

That won't work.

In your rosservice call invocation, you're passing lists again (stop_controllers: ['']). That's why it works.


Originally posted by gvdhoorn with karma: 86574 on 2021-12-17

This answer was ACCEPTED on the original site

Post score: 0

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.