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

Adding JointGroupVelocityControllers #224

Merged
merged 2 commits into from
Nov 1, 2018
Merged
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 README.md
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ The position based controller *should* stay closer to the commanded path, while

**Note** that the PID values are not optimally tweaked as of this moment.

To use ros_control together with MoveIt, be sure to add the desired controller to the ```controllers.yaml``` in the urXX_moveit_config/config folder. Add the following
To use ros_control together with MoveIt, be sure to add the desired controller to the ```controllers.yaml``` in the urXX_moveit_config/config folder. Add the following:

```yaml
controller_list:
Expand Down
10 changes: 10 additions & 0 deletions config/ur10_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -87,3 +87,13 @@ vel_based_pos_traj_controller:
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5

# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
11 changes: 11 additions & 0 deletions config/ur3_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -87,3 +87,14 @@ vel_based_pos_traj_controller:
# state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5

# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
10 changes: 10 additions & 0 deletions config/ur5_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -86,3 +86,13 @@ vel_based_pos_traj_controller:
# action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5

# Pass an array of joint velocities directly to the joints
joint_group_vel_controller:
type: velocity_controllers/JointGroupVelocityController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
2 changes: 1 addition & 1 deletion launch/ur10_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@

<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load pos_based_pos_traj_controller" />
output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" />

<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/ur3_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,9 @@

<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load pos_based_pos_traj_controller" />
output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" />

<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>

</launch>
</launch>
2 changes: 1 addition & 1 deletion launch/ur5_ros_control.launch
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@

<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load pos_based_pos_traj_controller" />
output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" />

<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
<exec_depend>joint_trajectory_controller</exec_depend>
<exec_depend>ur_description</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>velocity_controllers</exec_depend>

<test_depend>rosunit</test_depend>
</package>