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

using both JointTrajectoryController and JointPositionController at same time in ros_control

asked 2015-01-11 23:13:44 -0600

Kei Okada gravatar image

Hi,

I just follow the excellent ros_control tutorial at ( http://gazebosim.org/tutorials/?tut=r... ) and able to run robot in gazebo, that provide command interface for each joint

roslaunch rrbot_gazebo rrbot_world.launch
roslaunch rrbot_control rrbot_control.launch

Next, I'd like to control this robot from our application, so need to use JointTrajectoryAction (or FollowJointTrajectoryAction), so I added following code in rrbot_control

diff --git a/rrbot_control/config/rrbot_control.yaml b/rrbot_control/config/rrbot_control.yaml
index 9cbcf45..0f62b1a 100644
--- a/rrbot_control/config/rrbot_control.yaml
+++ b/rrbot_control/config/rrbot_control.yaml
@@ -13,3 +13,15 @@ rrbot:
     type: effort_controllers/JointPositionController
     joint: joint2
     pid: {p: 100.0, i: 0.01, d: 10.0}
+
+  # Trajectory Controllers ---------------------------------------
+  joint_trajectory_controller:
+    type: "effort_controllers/JointTrajectoryController"
+    joints:
+      - joint1
+      - joint2
+
+    gains: # Required because we're controlling an effort interface
+      joint1: {p: 100,  d: 1, i: 1, i_clamp: 1}
+      joint2: {p: 100,  d: 1, i: 1, i_clamp: 1}
+
diff --git a/rrbot_control/launch/rrbot_control.launch b/rrbot_control/launch/rrbot_control.launch
index 0a0c605..a4b1b2a 100644
--- a/rrbot_control/launch/rrbot_control.launch
+++ b/rrbot_control/launch/rrbot_control.launch
@@ -7,7 +7,9 @@
   <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
        output="screen" ns="/rrbot" args="joint_state_controller
                                          joint1_position_controller
-                                     joint2_position_controller"/>
+                                   joint2_position_controller
+                                   joint_trajectory_controller
+                                          "/>

   <!-- convert joint states to TF transforms for rviz, etc -->
   <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"

but I got have following error. Is it possible to run joint trajectory action while keeping ability to command value to each joint? I remember some real robto (pr2, baxter) has capable of this, so how do the archive that?

[ERROR] [WallTime: 1421039041.629407] [242.570000] Failed to start controllers: joint_state_controller, joint1_position_controller, joint2_position_controller, joint_trajectory_controller
[ WARN] [1421039041.629194844, 242.570000000]: Resource conflict on [joint1].  Controllers = [joint1_position_controller, joint_trajectory_controller, ]
[ WARN] [1421039041.629234042, 242.570000000]: Resource conflict on [joint2].  Controllers =    [joint2_position_controller, joint_trajectory_controller, ]
[ERROR] [1421039041.629256800, 242.570000000]: Could not switch controllers, due to resource conflict
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2015-01-23 02:53:13 -0600

Adolfo Rodriguez T gravatar image

Is it possible to run joint trajectory action while keeping ability to command value to each joint?

By commanding individual joints you mean the specific ROS API of JointPositionController?.

These are the options that currently exist:

  • Use the controller_manager/switch_controller service to stop the joint_trajectory_controller and start the joint_position_controller to change the currently running controllers.

  • If you normally use the joint_trajectory_controller, but sometimes want to change to the joint_position_controller, you can setup a launch file consisting of a spawner that starts the joint_position_controller and an unspawner for inhibitting (stopping) the joint_trajectory_controller. When you kill the roslaunch process and the spawner+unspawner die, you will revert back to the original controller configuration.

  • You can use only the joint_trajectory_controller. Because it only accepts commands for _all_ controller joints and not _some_, you can write a small node that takes in commands and adds the current joint state to the missing joints.

Solutions that don't yet exist:

  • Propose an enhancement to the joint_trajectory_controller so it can take trajectories not involving all group joints. There are likely subtle points to figure out to get the implementation right.

Solutions that I don't recommend, but you can implement if you want to:

  • Override the default resource conflict policy, so resource access is non-exclusive. Take into account that aloowing two controllers to send position commands to the same joint is not the best idea.
edit flag offensive delete link more
0

answered 2018-03-05 16:02:53 -0600

updated 2018-03-05 16:06:04 -0600

Based on the advice from Adolfo Rodriguez T. this worked for me:

<?xml version="1.0"?>
<launch>

    <!-- to switch arm sim from trajectory controller to position controller during runtime -->

    <!-- unspawn arm sim trajectory controller -->
    <node pkg="controller_manager" type="unspawner" name="traj_ctrl_unspawner" args="left_arm_traj_controller" />

    <!-- spawn arm sim position controller -->
    <node pkg="controller_manager" type="spawner" name="pos_ctrl_spawner"
          args="left_arm_joint0_position_controller
                left_arm_joint1_position_controller
                left_arm_joint2_position_controller
                left_arm_joint3_position_controller
                left_arm_joint4_position_controller
                left_arm_joint5_position_controller
                left_arm_joint6_position_controller" />

</launch>

Then an alias:

alias enable_pos_ctrl='roslaunch mbot_gazebo_control switch_from_traj_to_pos_ctrl.launch'

Once you kill the launch file it returns to its original controller (trajectory ctrl in my case).

edit flag offensive delete link more

Question Tools

Stats

Asked: 2015-01-11 23:13:44 -0600

Seen: 5,099 times

Last updated: Mar 05 '18