Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ur_simulation_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ project(ur_simulation_gazebo)

find_package(ament_cmake REQUIRED)

install(DIRECTORY config launch
install(DIRECTORY config launch urdf rviz
DESTINATION share/${PROJECT_NAME}
)

Expand Down
8 changes: 4 additions & 4 deletions ur_simulation_gazebo/launch/ur_sim_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

from launch_ros.descriptions import ParameterValue

def launch_setup(context, *args, **kwargs):

Expand Down Expand Up @@ -100,7 +100,7 @@ def launch_setup(context, *args, **kwargs):
initial_joint_controllers,
]
)
robot_description = {"robot_description": robot_description_content}
robot_description = {"robot_description": ParameterValue(robot_description_content, value_type=str)}

robot_state_publisher_node = Node(
package="robot_state_publisher",
Expand Down Expand Up @@ -226,15 +226,15 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
default_value="ur_description",
default_value="ur_simulation_gazebo",
description="Description package with robot URDF/XACRO files. Usually the argument \
is not set, it enables use of a custom description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="ur.urdf.xacro",
default_value="ur_gazebo_classic.urdf.xacro",
description="URDF/XACRO description file with the robot.",
)
)
Expand Down
5 changes: 3 additions & 2 deletions ur_simulation_gazebo/launch/ur_sim_moveit.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ def launch_setup(context, *args, **kwargs):
"prefix": prefix,
"use_sim_time": "true",
"launch_rviz": "true",
"use_fake_hardware": "true", #to get regular JTC instead of scaled JTC. What are the other consequences?
}.items(),
)

Expand Down Expand Up @@ -127,15 +128,15 @@ def generate_launch_description():
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
default_value="ur_description",
default_value="ur_simulation_gazebo", # TODO: UNTANGLE DEPS -> ur_moveit_config passes explicit joint limits, kinematics params, etc to the .urdf.xacro (probably for calibration, etc.) Do we duplicate all of the defaults?
description="Description package with robot URDF/XACRO files. Usually the argument \
is not set, it enables use of a custom description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="ur.urdf.xacro",
default_value="ur_gazebo_classic.urdf.xacro",
description="URDF/XACRO description file with the robot.",
)
)
Expand Down
196 changes: 196 additions & 0 deletions ur_simulation_gazebo/rviz/view_robot.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,196 @@
Panels:
- Class: rviz_common/Displays
Help Height: 87
Name: Displays
Property Tree Widget:
Expanded:
- /RobotModel1/Description Topic1
Splitter Ratio: 0.5
Tree Height: 1096
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
base_link_inertia:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
flange:
Alpha: 1
Show Axes: false
Show Trail: false
forearm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
shoulder_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
upper_arm_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_1_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_2_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
wrist_3_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 3.493516445159912
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -0.0457618348300457
Y: -0.07058511674404144
Z: 0.49734944105148315
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.15039828419685364
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.5353983640670776
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1379
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a000004f0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000007901000003fb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000048000004f00000010101000003fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000110000004f0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000048000004f0000000db01000003fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000784000004f000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 2560
X: 0
Y: 30
86 changes: 86 additions & 0 deletions ur_simulation_gazebo/urdf/ur_gazebo_classic.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">
<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>
<!-- import main macro -->
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>

<!-- possible 'ur_type' values: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e -->
<!-- the default value should raise an error in case this was called without defining the type -->
<xacro:arg name="ur_type" default="ur5x"/>

<!-- parameters -->
<xacro:arg name="tf_prefix" default="" />
<xacro:arg name="joint_limit_params" default="$(find ur_description)/config/$(arg ur_type)/joint_limits.yaml"/>
<xacro:arg name="kinematics_params" default="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"/>
<xacro:arg name="physical_params" default="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"/>
<xacro:arg name="visual_params" default="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"/>
<xacro:arg name="transmission_hw_interface" default=""/>
<xacro:arg name="safety_limits" default="false"/>
<xacro:arg name="safety_pos_margin" default="0.15"/>
<xacro:arg name="safety_k_position" default="20"/>
<xacro:arg name="simulation_controllers" default="" />

<!-- initial position for simulations (Fake Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>

<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<!-- create link fixed to the "world" -->
<link name="world" />
<!--
After #52 this will be less verbose
since read_model_data will be seperate from ur_robot
and we can modify just the properties we need
-->
<xacro:property name="jnt_limits_file" value="$(arg joint_limit_params)"/>
<xacro:property name="jnt_limits"
value="${xacro.load_yaml(jnt_limits_file)['joint_limits']}"
/>
<xacro:property name="fric_scale" value="100.0" />
<xacro:property name="joint_dyn_dict"
value="${dict(
joint_dynamics=dict(
shoulder_pan_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['shoulder_pan_joint']['max_effort']),
shoulder_lift_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['shoulder_lift_joint']['max_effort']),
elbow_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['elbow_joint']['max_effort']),
wrist_1_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['wrist_1_joint']['max_effort']),
wrist_2_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['wrist_2_joint']['max_effort']),
wrist_3_joint=dict(damping=0.0, friction=fric_scale*jnt_limits['wrist_3_joint']['max_effort'])))}"
/>
<param name="blah" value="${joint_dyn_dict}" />


<!-- arm -->

<xacro:ur_robot
name="$(arg name)"
tf_prefix="$(arg tf_prefix)"
parent="world"
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
safety_k_position="$(arg safety_k_position)"
joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(arg visual_params)"
joint_dynamics="${joint_dyn_dict}"
transmission_hw_interface=""
sim_gazebo="true"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
>
<origin xyz="0 0 0.05" rpy="0 0 0" />
</xacro:ur_robot>


<!-- Gazebo plugins -->
<gazebo reference="world">
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(arg simulation_controllers)</parameters>
</plugin>
</gazebo>

</robot>