41 lines
1.3 KiB
YAML
41 lines
1.3 KiB
YAML
controller_manager:
|
|
ros__parameters:
|
|
update_rate: 1000 # Hz
|
|
|
|
panda_arm_controller:
|
|
type: joint_trajectory_controller/JointTrajectoryController
|
|
|
|
joint_state_broadcaster:
|
|
type: joint_state_broadcaster/JointStateBroadcaster
|
|
|
|
franka_robot_state_broadcaster:
|
|
type: franka_robot_state_broadcaster/FrankaRobotStateBroadcaster
|
|
|
|
franka_robot_state_broadcaster:
|
|
ros__parameters:
|
|
arm_id: panda
|
|
|
|
panda_arm_controller:
|
|
ros__parameters:
|
|
command_interfaces:
|
|
- effort
|
|
state_interfaces:
|
|
- position
|
|
- velocity
|
|
joints:
|
|
- panda_joint1
|
|
- panda_joint2
|
|
- panda_joint3
|
|
- panda_joint4
|
|
- panda_joint5
|
|
- panda_joint6
|
|
- panda_joint7
|
|
gains:
|
|
panda_joint1: { p: 600., d: 30., i: 0., i_clamp: 1., ff_velocity_scale: 1.}
|
|
panda_joint2: { p: 600., d: 30., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|
|
panda_joint3: { p: 600., d: 30., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|
|
panda_joint4: { p: 600., d: 30., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|
|
panda_joint5: { p: 250., d: 10., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|
|
panda_joint6: { p: 150., d: 10., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|
|
panda_joint7: { p: 50., d: 5., i: 0., i_clamp: 1., ff_velocity_scale: 1. }
|