diff --git a/README.md b/README.md index 9c66e830..11048c7b 100644 --- a/README.md +++ b/README.md @@ -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: diff --git a/config/ur10_controllers.yaml b/config/ur10_controllers.yaml index eb9134bf..996e3e0e 100644 --- a/config/ur10_controllers.yaml +++ b/config/ur10_controllers.yaml @@ -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 \ No newline at end of file diff --git a/config/ur3_controllers.yaml b/config/ur3_controllers.yaml index 45b34f42..725ca3f9 100644 --- a/config/ur3_controllers.yaml +++ b/config/ur3_controllers.yaml @@ -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 \ No newline at end of file diff --git a/config/ur5_controllers.yaml b/config/ur5_controllers.yaml index a6c45695..82346588 100644 --- a/config/ur5_controllers.yaml +++ b/config/ur5_controllers.yaml @@ -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 \ No newline at end of file diff --git a/launch/ur10_ros_control.launch b/launch/ur10_ros_control.launch index 6eb9dd45..dfb9be4d 100644 --- a/launch/ur10_ros_control.launch +++ b/launch/ur10_ros_control.launch @@ -44,7 +44,7 @@ + output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" /> diff --git a/launch/ur3_ros_control.launch b/launch/ur3_ros_control.launch index 14993451..b8681e44 100644 --- a/launch/ur3_ros_control.launch +++ b/launch/ur3_ros_control.launch @@ -44,9 +44,9 @@ + output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" /> - + \ No newline at end of file diff --git a/launch/ur5_ros_control.launch b/launch/ur5_ros_control.launch index ccf5d792..d443c0e4 100644 --- a/launch/ur5_ros_control.launch +++ b/launch/ur5_ros_control.launch @@ -44,7 +44,7 @@ + output="screen" args="load pos_based_pos_traj_controller joint_group_vel_controller" /> diff --git a/package.xml b/package.xml index 41643df4..9a460dff 100644 --- a/package.xml +++ b/package.xml @@ -34,6 +34,7 @@ joint_trajectory_controller ur_description robot_state_publisher + velocity_controllers rosunit