Files
Uni-Lab-OS/unilabos/device_mesh/ros2_controllers.yaml
zhangshixiang 3d11a0cc50 unilab添加moveit启动
1,整合所有moveit节点到一个move_group中,并整合所有的controller依次激活
2,添加pymoveit2的节点,使用json可直接启动
3,修改机械臂规划方式,添加约束,让冗余关节不会进行过多移动
2025-06-06 22:09:35 +08:00

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