-
Notifications
You must be signed in to change notification settings - Fork 406
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Showing
2 changed files
with
110 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,62 @@ | ||
# Settings for ros_control control loop | ||
hardware_control_loop: | ||
loop_hz: &loop_hz 500 | ||
|
||
# Settings for ros_control hardware interface | ||
hardware_interface: | ||
joints: &robot_joints | ||
- shoulder_pan_joint | ||
- shoulder_lift_joint | ||
- elbow_joint | ||
- wrist_1_joint | ||
- wrist_2_joint | ||
- wrist_3_joint | ||
|
||
# Publish all joint states ---------------------------------- | ||
joint_state_controller: | ||
type: joint_state_controller/JointStateController | ||
publish_rate: *loop_hz | ||
|
||
# Publish wrench ---------------------------------- | ||
force_torque_sensor_controller: | ||
type: force_torque_sensor_controller/ForceTorqueSensorController | ||
publish_rate: *loop_hz | ||
|
||
# Publish speed_scaling factor | ||
speed_scaling_state_controller: | ||
type: ur_controllers/SpeedScalingStateController | ||
publish_rate: *loop_hz | ||
|
||
# Joint Trajectory Controller - position based ------------------------------- | ||
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller | ||
scaled_pos_traj_controller: | ||
type: position_controllers/ScaledJointTrajectoryController | ||
joints: *robot_joints | ||
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: *loop_hz | ||
action_monitor_rate: 10 | ||
|
||
pos_traj_controller: | ||
type: position_controllers/JointTrajectoryController | ||
joints: *robot_joints | ||
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: *loop_hz | ||
action_monitor_rate: 10 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
<?xml version="1.0"?> | ||
<launch> | ||
|
||
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/> | ||
<arg name="robot_ip" doc="IP address by which the robot can be reached."/> | ||
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/> | ||
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/> | ||
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/> | ||
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/> | ||
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/> | ||
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur16e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/> | ||
<arg name="robot_description_file" default="$(find ur_description)/launch/ur16e_upload.launch" doc="Robot description launch file."/> | ||
<arg name="kinematics_config" default="$(find ur_description)/config/ur16e/default_kinematics.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/> | ||
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/> | ||
<arg name="tool_voltage" default="0" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_stop_bits" default="1" doc="Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_rx_idle_chars" default="1.5" doc="Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> | ||
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/> | ||
|
||
<include file="$(find ur_robot_driver)/launch/ur_common.launch"> | ||
<arg name="debug" value="$(arg debug)"/> | ||
<arg name="use_tool_communication" value="$(arg use_tool_communication)"/> | ||
<arg name="controller_config_file" value="$(arg controller_config_file)"/> | ||
<arg name="robot_description_file" value="$(arg robot_description_file)"/> | ||
<arg name="kinematics_config" value="$(arg kinematics_config)"/> | ||
<arg name="robot_ip" value="$(arg robot_ip)"/> | ||
<arg name="reverse_port" value="$(arg reverse_port)"/> | ||
<arg name="script_sender_port" value="$(arg script_sender_port)"/> | ||
<arg name="tf_prefix" value="$(arg tf_prefix)"/> | ||
<arg name="controllers" value="$(arg controllers)"/> | ||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/> | ||
<arg name="headless_mode" value="$(arg headless_mode)"/> | ||
<arg name="tool_voltage" value="$(arg tool_voltage)"/> | ||
<arg name="tool_parity" value="$(arg tool_parity)"/> | ||
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/> | ||
<arg name="tool_stop_bits" value="$(arg tool_stop_bits)"/> | ||
<arg name="tool_rx_idle_chars" value="$(arg tool_rx_idle_chars)"/> | ||
<arg name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/> | ||
<arg name="tool_device_name" value="$(arg tool_device_name)"/> | ||
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/> | ||
</include> | ||
|
||
</launch> |