mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Merge pull request #79 from HurchelYoung/master
Minor corrections needed for default ros_control based approach
This commit is contained in:
13
README.md
13
README.md
@@ -52,13 +52,16 @@ If you want to test it in your current setup, just use the modified launch files
|
||||
---
|
||||
If you would like to use the ros\_control-based approach, use the launch files urXX\_ros\_control.launch, where XX is '5' or '10' depending on your robot.
|
||||
|
||||
The driver currently supports two position trajectory controllers; a position based and a velocity based. They are both loaded via the launch file, but only one of them can be running at the same time.
|
||||
You can switch controller by calling the appropriate service:
|
||||
**Note:** If you are using the ros\_control-based approach you will need 2 packages that can be found in the ur\_driver package. If you do not have the ur\_driver package in your workspace simply copy these packages into your workspace /src folder:
|
||||
* urXX_moveit_config
|
||||
* ur_description
|
||||
|
||||
The driver currently supports two position trajectory controllers; a position based and a velocity based. They are both loaded via the launch file, but only one of them can be running at the same time. By default the velocity based controller is started. You can switch controller by calling the appropriate service:
|
||||
```
|
||||
rosservice call /universal_robot/controller_manager/switch_controller "start_controllers:
|
||||
- 'velocity_based_position_trajectory_controller'
|
||||
- 'vel_based_pos_traj_controller'
|
||||
stop_controllers:
|
||||
- 'position_based_position_trajectory_controller'
|
||||
- 'pos_based_pos_traj_controller'
|
||||
strictness: 1"
|
||||
```
|
||||
Be sure to stop the currently running controller **either before or in the same call** as you start a new one, otherwise it will fail.
|
||||
@@ -70,7 +73,7 @@ The position based controller *should* stay closer to the commanded path, while
|
||||
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
|
||||
```
|
||||
controller_list:
|
||||
- name: vel_based_pos_traj_controller #or pos_based_pos_traj_controller
|
||||
- name: /vel_based_pos_traj_controller #or /pos_based_pos_traj_controller
|
||||
action_ns: follow_joint_trajectory
|
||||
type: FollowJointTrajectory
|
||||
default: true
|
||||
|
||||
@@ -26,7 +26,7 @@ force_torque_sensor_controller:
|
||||
|
||||
# Joint Trajectory Controller - position based -------------------------------
|
||||
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
|
||||
position_based_position_trajectory_controller:
|
||||
pos_based_pos_traj_controller:
|
||||
type: position_controllers/JointTrajectoryController
|
||||
joints:
|
||||
- shoulder_pan_joint
|
||||
@@ -54,7 +54,7 @@ position_based_position_trajectory_controller:
|
||||
|
||||
# Joint Trajectory Controller - velocity based -------------------------------
|
||||
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
|
||||
velocity_based_position_trajectory_controller:
|
||||
vel_based_pos_traj_controller:
|
||||
type: velocity_controllers/JointTrajectoryController
|
||||
joints:
|
||||
- shoulder_pan_joint
|
||||
|
||||
Reference in New Issue
Block a user