Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add a JointTrajectoryController config #186

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion franka_control/config/default_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
position_joint_trajectory_controller:
position_joint_trajectory_controller: &default_trajectory_controller
type: position_controllers/JointTrajectoryController
joints:
- panda_joint1
Expand All @@ -25,6 +25,9 @@ position_joint_trajectory_controller:
panda_joint7:
goal: 0.05

# define default controller for panda_moveit_config:
joint_trajectory_controller: *default_trajectory_controller

franka_state_controller:
type: franka_control/FrankaStateController
publish_rate: 30 # [Hz]
Expand Down
22 changes: 22 additions & 0 deletions franka_gazebo/config/sim_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,28 @@ franka_state_controller:
- $(arg arm_id)_joint6
- $(arg arm_id)_joint7

effort_joint_trajectory_controller: &default_trajectory_controller
type: effort_controllers/JointTrajectoryController
joints:
- $(arg arm_id)_joint1
- $(arg arm_id)_joint2
- $(arg arm_id)_joint3
- $(arg arm_id)_joint4
- $(arg arm_id)_joint5
- $(arg arm_id)_joint6
- $(arg arm_id)_joint7
gains:
$(arg arm_id)_joint1: { p: 600, d: 30, i: 0 }
$(arg arm_id)_joint2: { p: 600, d: 30, i: 0 }
$(arg arm_id)_joint3: { p: 600, d: 30, i: 0 }
$(arg arm_id)_joint4: { p: 600, d: 30, i: 0 }
$(arg arm_id)_joint5: { p: 250, d: 10, i: 0 }
$(arg arm_id)_joint6: { p: 150, d: 10, i: 0 }
$(arg arm_id)_joint7: { p: 50, d: 5, i: 0 }

# define default controller for panda_moveit_config:
joint_trajectory_controller: *default_trajectory_controller

model_example_controller:
type: franka_example_controllers/ModelExampleController
arm_id: $(arg arm_id)
Expand Down