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

ros_canopen Profile position + Interpolated position modes

asked 2019-08-20 02:02:55 -0600

akosodry gravatar image

updated 2019-08-20 02:04:31 -0600

Hello.

I'm working on a custom made robotic arm actuated by different motion controllers/motors via ros_canopen. Currently, the motors are controlled in profile position mode defined in the relevant yaml config file as follows:

robot_5s_arm_joint_controller:
  type: "position_controllers/JointTrajectoryController"
  joints:
    - joint_1
    - joint_2
    - joint_3
    - joint_4
    - joint_5

  required_drive_mode: 1

Due to some mechanical issues, i need to change the required_drive_mode to Interpolated position mode, but only three controllers (joint1-3) support this mode, the rest (joint4-5) can only be driven in profile position mode.

So the question is, what is the workaround here? :)

I suppose, that two arm_joint_controller groups shall be defined, one (joint1-3) with required_drive_mode: 7 and the other with required_drive_mode: 1. Then simply, in the moveit controller yaml file, i can define these controllers? Is this enough?

Do i need to change the planning group defined in moveit?

Thank you in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2019-08-20 02:56:51 -0600

Mathias Lüdtke gravatar image

So the question is, what is the workaround here? :)

You can specify mixed modes

I suppose, that two arm_joint_controller groups shall be defined, one (joint1-3) with required_drive_mode: 7 and the other with required_drive_mode: 1

Much simpler: you can define a default mode (required_drive_mode, singular) and add a look-up (required_drive_modes, plural) for the others:

robot_5s_arm_joint_controller:
  type: "position_controllers/JointTrajectoryController"
  joints:
    - joint_1
    - joint_2
    - joint_3
    - joint_4
    - joint_5

  required_drive_mode: 7
  required_drive_modes:
    joint_4: 1
    joint_5: 1

or you set all explicitly:

robot_5s_arm_joint_controller:
  type: "position_controllers/JointTrajectoryController"
  joints:
    - joint_1
    - joint_2
    - joint_3
    - joint_4
    - joint_5

  required_drive_modes:
    joint_1: 7
    joint_2: 7
    joint_3: 7
    joint_4: 1
    joint_5: 1

Then simply, in the moveit controller yaml file, i can define these controllers? Is this enough?

Not needed.

Do i need to change the planning group defined in moveit?

Nope :)

edit flag offensive delete link more

Comments

wow! THANKS!!!

akosodry gravatar image akosodry  ( 2019-08-20 03:08:52 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2019-08-20 02:02:55 -0600

Seen: 169 times

Last updated: Aug 20 '19