1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-09 17:40:47 +02:00

define a non-scaled position trajectory controller by default

This way, users can choose whether they want to use non-scaled controllers
as used by older drivers.
This commit is contained in:
Felix Mauch
2019-06-26 08:54:29 +02:00
parent 5934de2772
commit cb64e68100
14 changed files with 154 additions and 22 deletions

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -29,7 +29,7 @@ speed_scaling_state_controller:
# Joint Trajectory Controller - position based -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
pos_based_pos_traj_controller:
scaled_pos_traj_controller:
type: position_controllers/ScaledJointTrajectoryController
joints:
- shoulder_pan_joint
@@ -50,3 +50,25 @@ pos_based_pos_traj_controller:
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10
pos_traj_controller:
type: position_controllers/JointTrajectoryController
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
elbow_joint: {trajectory: 0.2, goal: 0.1}
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 500
action_monitor_rate: 10

View File

@@ -10,8 +10,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/>

View File

@@ -11,8 +11,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<arg name="tool_voltage" default="12"/>
<arg name="tool_parity" default="0"/>
<arg name="tool_baud_rate" default="115200"/>

View File

@@ -10,8 +10,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/>

View File

@@ -11,8 +11,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<arg name="tool_voltage" default="12"/>
<arg name="tool_parity" default="0"/>
<arg name="tool_baud_rate" default="115200"/>

View File

@@ -10,8 +10,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/>

View File

@@ -11,8 +11,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<arg name="tool_voltage" default="12"/>
<arg name="tool_parity" default="0"/>
<arg name="tool_baud_rate" default="115200"/>

View File

@@ -8,8 +8,8 @@
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<arg name="tool_voltage" default="12"/>
<arg name="tool_parity" default="0"/>
<arg name="tool_baud_rate" default="115200"/>

View File

@@ -11,8 +11,8 @@
<arg name="robot_ip"/>
<arg name="kinematics_config"/>
<arg name="tf_prefix" default="" />
<arg name="controllers" default="joint_state_controller pos_based_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default=""/>
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
<arg name="stopped_controllers" default="pos_traj_controller"/>
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/>
<arg name="rtde_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_recipe.txt"/>
<arg name="tool_voltage" default="12"/>