mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Adding JointGroupVelocityControllers (#224)
* Adding JointGroupVelocityControllers. * Correction re. ros_control in Readme. Add velocity_controllers dependency.
This commit is contained in:
@@ -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:
|
||||
|
||||
@@ -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
|
||||
@@ -94,3 +94,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
|
||||
@@ -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
|
||||
@@ -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"/>
|
||||
|
||||
@@ -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>
|
||||
@@ -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"/>
|
||||
|
||||
@@ -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>
|
||||
|
||||
Reference in New Issue
Block a user