mirror of
https://github.com/dptech-corp/Uni-Lab-OS.git
synced 2025-12-17 04:51:10 +00:00
1,整合所有moveit节点到一个move_group中,并整合所有的controller依次激活 2,添加pymoveit2的节点,使用json可直接启动 3,修改机械臂规划方式,添加约束,让冗余关节不会进行过多移动
32 lines
814 B
YAML
32 lines
814 B
YAML
benyao_arm_controller:
|
|
ros__parameters:
|
|
command_interfaces:
|
|
- position
|
|
joints:
|
|
- benyao_arm_base_joint
|
|
- benyao_arm_link_1_joint
|
|
- benyao_arm_link_2_joint
|
|
- benyao_arm_link_3_joint
|
|
- benyao_gripper_base_joint
|
|
state_interfaces:
|
|
- position
|
|
- velocity
|
|
benyao_gripper_controller:
|
|
ros__parameters:
|
|
command_interfaces:
|
|
- position
|
|
joints:
|
|
- benyao_gripper_right_joint
|
|
state_interfaces:
|
|
- position
|
|
- velocity
|
|
controller_manager:
|
|
ros__parameters:
|
|
benyao_arm_controller:
|
|
type: joint_trajectory_controller/JointTrajectoryController
|
|
benyao_gripper_controller:
|
|
type: joint_trajectory_controller/JointTrajectoryController
|
|
joint_state_broadcaster:
|
|
type: joint_state_broadcaster/JointStateBroadcaster
|
|
update_rate: 100
|