ROS Components for hexapod_robot
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

81 lines
1.7KB

  1. # MoveIt uses this configuration for controller management
  2. moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
  3. moveit_simple_controller_manager:
  4. controller_names:
  5. - e1_group_controller
  6. - e2_group_controller
  7. - e3_group_controller
  8. - e4_group_controller
  9. - e5_group_controller
  10. - e6_group_controller
  11. e1_group_controller:
  12. type: FollowJointTrajectory
  13. action_ns: follow_joint_trajectory
  14. default: true
  15. joints:
  16. - c1_joint
  17. - f1_joint
  18. - t1_joint
  19. action_ns: follow_joint_trajectory
  20. default: true
  21. e2_group_controller:
  22. type: FollowJointTrajectory
  23. action_ns: follow_joint_trajectory
  24. default: true
  25. joints:
  26. - c2_joint
  27. - f2_joint
  28. - t2_joint
  29. action_ns: follow_joint_trajectory
  30. default: true
  31. e3_group_controller:
  32. type: FollowJointTrajectory
  33. action_ns: follow_joint_trajectory
  34. default: true
  35. joints:
  36. - c3_joint
  37. - f3_joint
  38. - t3_joint
  39. action_ns: follow_joint_trajectory
  40. default: true
  41. e4_group_controller:
  42. type: FollowJointTrajectory
  43. action_ns: follow_joint_trajectory
  44. default: true
  45. joints:
  46. - c4_joint
  47. - f4_joint
  48. - t4_joint
  49. action_ns: follow_joint_trajectory
  50. default: true
  51. e5_group_controller:
  52. type: FollowJointTrajectory
  53. action_ns: follow_joint_trajectory
  54. default: true
  55. joints:
  56. - c5_joint
  57. - f5_joint
  58. - t5_joint
  59. action_ns: follow_joint_trajectory
  60. default: true
  61. e6_group_controller:
  62. type: FollowJointTrajectory
  63. action_ns: follow_joint_trajectory
  64. default: true
  65. joints:
  66. - c6_joint
  67. - f6_joint
  68. - t6_joint
  69. action_ns: follow_joint_trajectory
  70. default: true