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

Difference between arm_controller and joint_group_position_controller

asked 2020-07-03 10:16:38 -0600

dimitri gravatar image

Hi

Can anyone explain to me what arm_controller and joint_group_position_controller in universal robots work? And what is their difference? I get that they are both used for controlling the joints (by position, velocity or effort) but why are both of them needed?

edit retag flag offensive close merge delete

Comments

What is arm_controller?

DangTran gravatar image DangTran  ( 2020-07-03 10:22:55 -0600 )edit

In universal_robot/ur_gazebo/arm_controller_ur3.yaml there are two different controllers defined: arm_controller and joint_group_position_controller

dimitri gravatar image dimitri  ( 2020-07-03 10:34:26 -0600 )edit

arm_controller used for trajectory position_controllers/JointTrajectoryController, while joint_group_position_controller is for group of joint controllers (position_controllers/JointGroupPositionController). Basically, arm_controller control the robot by trajectory calculated from planning, while joint_group_position_controller can control the robot follow manually user's input.

DangTran gravatar image DangTran  ( 2020-07-03 10:43:53 -0600 )edit

If you want to control robot's joint, such as shoulder_pan_joint=0.1, you can do that by sending command to topic, then joint_group_position_controller is the one you want to focus on. If you want to automatically compute trajectory given goal target pose, then arm_controller is the one you will work with.

DangTran gravatar image DangTran  ( 2020-07-03 10:53:25 -0600 )edit

Ok thank you very much. That cleared up things. If you post it as an answer than I can mark it as the correct answer.

dimitri gravatar image dimitri  ( 2020-07-03 11:08:11 -0600 )edit

If you want to automatically compute trajectory given goal target pose, then arm_controller is the one you will work with.

this is actually only partially correct.

The main use-case for the JointTrajectoryController is to execute pre-calculated trajectory_msgs/JointTrajectory. The command topic does indeed accept individual JointTrajectoryPoints, but I would consider that secondary functionality.

gvdhoorn gravatar image gvdhoorn  ( 2020-07-03 11:38:01 -0600 )edit

@gvdhoorn I totally agree with you. My answer emphasizes more on the difference in application scenarios rather than functionalities. Quite like a personal trick to remember things :)

DangTran gravatar image DangTran  ( 2020-07-03 11:51:14 -0600 )edit

My answer emphasizes more on the difference in application scenarios rather than functionalities

well if that's the case then wouldn't the biggest difference be that a JointTrajectoryController can execute trajectories while a JointGroupPositionController cannot and is only used for forwarding single position setpoints to a group of joints?

gvdhoorn gravatar image gvdhoorn  ( 2020-07-03 11:54:54 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2020-07-03 11:18:35 -0600

DangTran gravatar image

updated 2020-07-03 12:16:15 -0600

To sum thing up, the controller file arm_controller_ur3.yaml is follows:

arm_controller:
  type: position_controllers/JointTrajectoryController
  joints:
     - shoulder_pan_joint
     - shoulder_lift_joint
     - elbow_joint
     - wrist_1_joint
     - wrist_2_joint
     - wrist_3_joint
  constraints:
      goal_time: 0.6
      stopped_velocity_tolerance: 0.05
      shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
      shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
      elbow_joint: {trajectory: 0.1, goal: 0.1}
      wrist_1_joint: {trajectory: 0.1, goal: 0.1}
      wrist_2_joint: {trajectory: 0.1, goal: 0.1}
      wrist_3_joint: {trajectory: 0.1, goal: 0.1}
  stop_trajectory_duration: 0.5
  state_publish_rate:  25
  action_monitor_rate: 10
joint_group_position_controller:
  type: position_controllers/JointGroupPositionController
  joints:
     - shoulder_pan_joint
     - shoulder_lift_joint
     - elbow_joint
     - wrist_1_joint
     - wrist_2_joint
     - wrist_3_joint

where arm_controller and joint_group_position_controller is just controller names, which can be whatever you like. The main difference here is arm_controller use JointTrajectoryController, so you can control the robot with trajectory messages computed from trajectory planners etc. While joint_group_position_controller uses JointGroupPositionController to control the robot's joint by directly sending values to controller manager.

To work with arm_controller, you have to understand message type trajectory_msgs/JointTrajectoryPoint, to define a movement of robot through time. While in joint_group_position_controller, you can simply specify each joint a value (no time involve)

edit flag offensive delete link more

Comments

Two Questions: Can you provide an example of publishing commands using the /arm_controller/command topic in the terminal? How can I use the Joint Group Velocity Controller instead of the Joint Group Position Controller?

Here's an example of me trying to publish trajectory_msgs/JointTrajectory:

rostopic pub -r 1 /arm_controller/command trajectory_msgs/JointTrajectory "header: seq: 0 stamp: secs: 0 nsecs: 0 frame_id: '' joint_names: - 'shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint' points: - positions: [1] velocities: [1] accelerations: [0] effort: [0] time_from_start: {secs: 1, nsecs: 0}"

The error that I receive is: Cannot create trajectory from message. It does not contain the expected joints.

StewartHemm74 gravatar image StewartHemm74  ( 2020-09-01 08:05:01 -0600 )edit
1

Usually, trajectory is the results from the planner, of course you can design a trajectory manually, it is quite tedious. Have a look at this link, it provides good example for publishing trajectory messages. For the JointGroupVelocityController, you probably have to change the <hardwareInterface> tags

DangTran gravatar image DangTran  ( 2020-09-01 10:04:04 -0600 )edit

thanks I'll check try that

StewartHemm74 gravatar image StewartHemm74  ( 2020-09-01 10:06:11 -0600 )edit
1

I realize it's been almost a year since this answer, but for others who might be interested, I'd like to add an alternative expression to use the joint trajectory controller's the topic interface here.

Obvi, do be careful about how you pick the joint angles here bc if you're using the real robot you may actually hurt something or someone, so, with that in mind, this following command should move the robot from all zeros (initial configuration in Gazebo for example) to 90 degrees for the shoulder pan joint in 2 secs.

rostopic pub /arm_controller/command trajectory_msgs/JointTrajectory '{header: {stamp: {secs: 0,nsecs: 0}}, joint_names: ['shoulder_pan_joint','shoulder_lift_joint','elbow_joint','wrist_1_joint'
,'wrist_2_joint','wrist_3_joint'], points: [{positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], time_from_start: {secs: 0.0, nsecs: 0.0}},{positions: [1.57, 0.0, 0.0, 0.0, 0.0, 0.0], time_from_start ...
(more)
bener suay gravatar image bener suay  ( 2021-04-15 12:35:18 -0600 )edit
2

answered 2021-04-15 13:23:32 -0600

Joint Group Position Controller should be seen as the raw-est form possible of setting goal positions for your robot's joints based on whatever their controller parameters (e.g. pd) are set. As the name suggests, you will not be sending a trajectory here and mimicking an accurate & timely trajectory controller with this interface will be really difficult due to timing and status check delays between your computer and the robot's output. This controller is not meant for trajectories, it's meant for setting positions (or joint angles) for a group of motors.

The trajectory controller on the other hand, provides feedback on the state of the trajectory while the trajectory is being executed. For instance, after you define a trajectory for your robot to move between 2 pre-defined configurations, the traj control interface computes the errors for you and packs it nicely with the current velocities and accelerations of your robot through its /state topic and /query_state service interfaces. This comes in handy for when you want your robot to start doing motions one after another so you can implement, for example, a state machine for your robot's pick-and-place task.

Sure, for the most simple case of moving 1 joint from 0.0 to 1.57 both controllers may end up delivering the same final results for your simulation, but the biggest difference between the two methods is what the control is applied to (positions vs. trajectories-made-of-positions specifically for position_controllers/JointGroupPositionController vs. position_controllers/JointTrajectoryController).

Hope this helps someone who is looking for answers.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2020-07-03 10:16:38 -0600

Seen: 2,346 times

Last updated: Apr 15 '21