This commit is contained in:
parent
8aad6559b3
commit
3298016e2d
@ -30,7 +30,9 @@ controller_manager:
|
|||||||
type: joint_trajectory_controller/JointTrajectoryController
|
type: joint_trajectory_controller/JointTrajectoryController
|
||||||
|
|
||||||
left_gripper_controller:
|
left_gripper_controller:
|
||||||
type: position_controllers/GripperActionController
|
type: forward_command_controller/ForwardCommandController
|
||||||
|
#使用action控制器时,注释掉上面type参数,使用下面的参数配置
|
||||||
|
# type: position_controllers/GripperActionController
|
||||||
|
|
||||||
right_forward_position_controller:
|
right_forward_position_controller:
|
||||||
type: forward_command_controller/ForwardCommandController
|
type: forward_command_controller/ForwardCommandController
|
||||||
@ -42,7 +44,9 @@ controller_manager:
|
|||||||
type: joint_trajectory_controller/JointTrajectoryController
|
type: joint_trajectory_controller/JointTrajectoryController
|
||||||
|
|
||||||
right_gripper_controller:
|
right_gripper_controller:
|
||||||
type: position_controllers/GripperActionController
|
type: forward_command_controller/ForwardCommandController
|
||||||
|
#使用action控制器时,注释掉上面type参数,使用下面的参数配置
|
||||||
|
# type: position_controllers/GripperActionController
|
||||||
|
|
||||||
|
|
||||||
left_forward_position_controller:
|
left_forward_position_controller:
|
||||||
@ -103,11 +107,15 @@ left_joint_trajectory_controller:
|
|||||||
|
|
||||||
left_gripper_controller:
|
left_gripper_controller:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
joint: openarm_left_finger_joint1
|
joints:
|
||||||
command_interfaces:
|
- openarm_left_finger_joint1
|
||||||
- position
|
interface_name: position
|
||||||
state_interfaces:
|
# 使用action控制器时,注释掉上面interface_name和joints参数,使用下面的参数配置
|
||||||
- position
|
# joint: openarm_left_finger_joint1
|
||||||
|
# command_interfaces:
|
||||||
|
# - position
|
||||||
|
# state_interfaces:
|
||||||
|
# - position
|
||||||
|
|
||||||
|
|
||||||
right_forward_position_controller:
|
right_forward_position_controller:
|
||||||
@ -168,8 +176,12 @@ right_joint_trajectory_controller:
|
|||||||
|
|
||||||
right_gripper_controller:
|
right_gripper_controller:
|
||||||
ros__parameters:
|
ros__parameters:
|
||||||
joint: openarm_right_finger_joint1
|
joints:
|
||||||
command_interfaces:
|
- openarm_right_finger_joint1
|
||||||
- position
|
interface_name: position
|
||||||
state_interfaces:
|
# 使用action控制器时,注释掉上面interface_name和joints参数,使用下面的参数配置
|
||||||
- position
|
# joint: openarm_right_finger_joint1
|
||||||
|
# command_interfaces:
|
||||||
|
# - position
|
||||||
|
# state_interfaces:
|
||||||
|
# - position
|
||||||
Loading…
Reference in New Issue
Block a user