gazebo显示完成
This commit is contained in:
@@ -1,12 +1,15 @@
|
||||
six_axis_arm:
|
||||
# 状态发布
|
||||
joint_state_controller:
|
||||
type: joint_state_controller/JointStateController
|
||||
publish_rate: 50
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 50
|
||||
|
||||
# 轨迹控制
|
||||
arm_position_controller:
|
||||
type: position_controllers/JointTrajectoryController # 使用关节轨迹控制器:让机器人按照轨迹运动到目标位置
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
||||
arm_position_controller:
|
||||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
arm_position_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- joint1
|
||||
- joint2
|
||||
@@ -14,11 +17,15 @@ six_axis_arm:
|
||||
- joint4
|
||||
- joint5
|
||||
- joint6
|
||||
command_interfaces:
|
||||
- position
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
gains:
|
||||
# 每个关节的PID增益设置
|
||||
joint1: { p: 100, d: 10, i: 0.01 }
|
||||
joint2: { p: 100, d: 10, i: 0.01 }
|
||||
joint3: { p: 100, d: 10, i: 0.01 }
|
||||
joint4: { p: 100, d: 10, i: 0.01 }
|
||||
joint5: { p: 100, d: 10, i: 0.01 }
|
||||
joint6: { p: 100, d: 10, i: 0.01 }
|
||||
joint1: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
joint2: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
joint3: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
joint4: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
joint5: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
joint6: { p: 100.0, d: 10.0, i: 0.01 }
|
||||
|
||||
Reference in New Issue
Block a user