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

[Gazebo] Add (but commented) the pid parameters for the position controller #443

Open
wants to merge 1 commit into
base: kinetic-devel
Choose a base branch
from
Open
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
2 changes: 1 addition & 1 deletion ur_description/urdf/common.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@

<gazebo>
<plugin name="ros_control" filename="libgazebo_ros_control.so">
<!--robotNamespace>/</robotNamespace-->
<!--robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType-->
<legacyModeNS>true</legacyModeNS>
</plugin>

<!--
Expand Down
11 changes: 11 additions & 0 deletions ur_gazebo/controller/arm_controller_ur10.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,3 +29,14 @@ joint_group_position_controller:
- wrist_2_joint
- wrist_3_joint

#Although Gazebo 7 requires the defition of the pid parameters for a the position controller, this is not working.
#Please uncomment the following lines for Gazebo or gazebo_ros_control upgrades

#gazebo_ros_control:
# pid_gains:
# shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1}
12 changes: 12 additions & 0 deletions ur_gazebo/controller/arm_controller_ur3.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,3 +29,15 @@ joint_group_position_controller:
- wrist_2_joint
- wrist_3_joint


#Although Gazebo 7 requires the defition of the pid parameters for a the position controller, this is not working.
#Please uncomment the following lines for Gazebo or gazebo_ros_control upgrades

#gazebo_ros_control:
# pid_gains:
# shoulder_pan_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# shoulder_lift_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# elbow_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_1_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_2_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_3_joint: {p: 50.0, i: 0.0, d: 0.1, i_clamp: 1}
11 changes: 11 additions & 0 deletions ur_gazebo/controller/arm_controller_ur5.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,3 +29,14 @@ joint_group_position_controller:
- wrist_2_joint
- wrist_3_joint

#Although Gazebo 7 requires the defition of the pid parameters for a the position controller, this is not working.
#Please uncomment the following lines for Gazebo or gazebo_ros_control upgrades

#gazebo_ros_control:
# pid_gains:
# shoulder_pan_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}
# shoulder_lift_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}
# elbow_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_1_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_2_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}
# wrist_3_joint: {p: 1.2, i: 0.0, d: 0.1, i_clamp: 1}