Merge branch 'main' into 77-cartesian-controllers
This commit is contained in:
commit
2755209c66
144 changed files with 100976 additions and 4303 deletions
|
@ -20,7 +20,7 @@ def generate_launch_description():
|
|||
"prefix": "",
|
||||
"sim_mujoco": "true",
|
||||
"simulation_controllers": str(initial_joint_controllers_file_path),
|
||||
"with_gripper": "false"
|
||||
"with_gripper": "true"
|
||||
})
|
||||
|
||||
robot_desc = doc.toprettyxml(indent=' ')
|
||||
|
|
|
@ -34,8 +34,9 @@ def generate_launch_description():
|
|||
env_manager_cond = LaunchConfiguration("env_manager")
|
||||
gazebo_gui = LaunchConfiguration("gazebo_gui")
|
||||
# FIXME: To args when we'll have different files
|
||||
# TODO: Use global variable to find world file in robossembler_db
|
||||
world_config_file = PathJoinSubstitution(
|
||||
[FindPackageShare("rbs_simulation"), "worlds", "mir.sdf"]
|
||||
[FindPackageShare("rbs_simulation"), "worlds", "asm2.sdf"]
|
||||
)
|
||||
# Gazebo nodes
|
||||
|
||||
|
@ -63,16 +64,45 @@ def generate_launch_description():
|
|||
'-topic', '/robot_description'],
|
||||
output='screen',
|
||||
condition=IfCondition(sim_gazebo))
|
||||
|
||||
env_manager = Node(package="env_manager",
|
||||
executable="env_manager_node",
|
||||
executable="run_env_manager",
|
||||
condition=IfCondition(env_manager_cond)
|
||||
)
|
||||
|
||||
# Bridge
|
||||
rgbd_bridge_out = Node(
|
||||
package='ros_gz_bridge',
|
||||
executable='parameter_bridge',
|
||||
arguments=[
|
||||
'/outer_rgbd_camera/image@sensor_msgs/msg/Image@gz.msgs.Image',
|
||||
'/outer_rgbd_camera/camera_info@sensor_msgs/msg/CameraInfo@gz.msgs.CameraInfo',
|
||||
'/outer_rgbd_camera/depth_image@sensor_msgs/msg/Image@gz.msgs.Image',
|
||||
'/outer_rgbd_camera/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked'
|
||||
],
|
||||
output='screen',
|
||||
condition=IfCondition(sim_gazebo)
|
||||
)
|
||||
|
||||
rgbd_bridge_in = Node(
|
||||
package='ros_gz_bridge',
|
||||
executable='parameter_bridge',
|
||||
arguments=[
|
||||
'/inner_rgbd_camera/image@sensor_msgs/msg/Image@gz.msgs.Image',
|
||||
'/inner_rgbd_camera/camera_info@sensor_msgs/msg/CameraInfo@gz.msgs.CameraInfo',
|
||||
'/inner_rgbd_camera/depth_image@sensor_msgs/msg/Image@gz.msgs.Image',
|
||||
'/inner_rgbd_camera/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked'
|
||||
],
|
||||
output='screen',
|
||||
)
|
||||
|
||||
|
||||
|
||||
nodes_to_start = [
|
||||
gazebo,
|
||||
gazebo_server,
|
||||
gazebo_spawn_robot,
|
||||
env_manager
|
||||
env_manager,
|
||||
rgbd_bridge_out,
|
||||
rgbd_bridge_in
|
||||
]
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
||||
|
|
BIN
rbs_simulation/models/fork/meshes/collision/fork.stl
Normal file
BIN
rbs_simulation/models/fork/meshes/collision/fork.stl
Normal file
Binary file not shown.
159
rbs_simulation/models/fork/meshes/visual/fork.dae
Normal file
159
rbs_simulation/models/fork/meshes/visual/fork.dae
Normal file
File diff suppressed because one or more lines are too long
14
rbs_simulation/models/fork/model.config
Normal file
14
rbs_simulation/models/fork/model.config
Normal file
|
@ -0,0 +1,14 @@
|
|||
<?xml version="1.0"?>
|
||||
<model>
|
||||
<name>fork</name>
|
||||
<sdf version="1.9">model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>bill-finger</name>
|
||||
<email>ur.narmak@gmail.com</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
The fork link of rbs_arm
|
||||
</description>
|
||||
</model>
|
58
rbs_simulation/models/fork/model.sdf
Normal file
58
rbs_simulation/models/fork/model.sdf
Normal file
|
@ -0,0 +1,58 @@
|
|||
<?xml version="1.0" ?>
|
||||
<sdf version="1.9">
|
||||
<model name="fork">
|
||||
<pose>0 0 0.015 0 0 0</pose>
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>0.00004167</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<ixz>0.0</ixz>
|
||||
<iyy>0.00004167</iyy>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.00004167</izz>
|
||||
</inertia>
|
||||
<mass>0.1</mass>
|
||||
</inertial>
|
||||
<!-- <gravity>0</gravity> -->
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>meshes/collision/fork.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode>
|
||||
<slip>
|
||||
0.3
|
||||
</slip>
|
||||
</ode>
|
||||
</torsional>
|
||||
<ode>
|
||||
<mu>0.2</mu>
|
||||
<mu2>0.2</mu2>
|
||||
</ode>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>meshes/visual/fork.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<!-- <material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material> -->
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
107
rbs_simulation/worlds/asm2.sdf
Normal file
107
rbs_simulation/worlds/asm2.sdf
Normal file
|
@ -0,0 +1,107 @@
|
|||
<?xml version="1.0"?>
|
||||
<sdf version='1.9'>
|
||||
<world name='asm2'>
|
||||
<physics name='1ms' type='ignored'>
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
<real_time_update_rate>1000</real_time_update_rate>
|
||||
</physics>
|
||||
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
|
||||
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
|
||||
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
|
||||
<plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
|
||||
<plugin name="ignition::gazebo::systems::Sensors" filename="ignition-gazebo-sensors-system">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<gravity>0 0 -9.8</gravity>
|
||||
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
|
||||
<atmosphere type='adiabatic'/>
|
||||
<scene>
|
||||
<ambient>0.4 0.4 0.4 1</ambient>
|
||||
<background>0.7 0.7 0.7 1</background>
|
||||
<shadows>false</shadows>
|
||||
</scene>
|
||||
<gui fullscreen="0">
|
||||
<plugin filename="GzScene3D" name="3D View">
|
||||
<ignition-gui>
|
||||
<title>3D View</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="string" key="state">docked</property>
|
||||
</ignition-gui>
|
||||
<engine>ogre2</engine>
|
||||
<scene>scene</scene>
|
||||
<ambient_light>1.0 1.0 1.0</ambient_light>
|
||||
<background_color>0.4 0.6 1.0</background_color>
|
||||
<camera_pose>3.3 2.8 2.8 0 0.5 -2.4</camera_pose>
|
||||
</plugin>
|
||||
<plugin filename="WorldStats" name="World stats">
|
||||
<ignition-gui>
|
||||
<title>World stats</title>
|
||||
<property type="bool" key="showTitleBar">false</property>
|
||||
<property type="bool" key="resizable">false</property>
|
||||
<property type="double" key="height">110</property>
|
||||
<property type="double" key="width">290</property>
|
||||
<property type="double" key="z">1</property>
|
||||
<property type="string" key="state">floating</property>
|
||||
<anchors target="3D View">
|
||||
<line own="right" target="right"/>
|
||||
<line own="bottom" target="bottom"/>
|
||||
</anchors>
|
||||
</ignition-gui>
|
||||
<sim_time>true</sim_time>
|
||||
<real_time>true</real_time>
|
||||
<real_time_factor>true</real_time_factor>
|
||||
<iterations>true</iterations>
|
||||
</plugin>
|
||||
</gui>
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
<pose>0 0 10 0 0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
<model name='ground'>
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<!-- Manipulating objects -->
|
||||
<include>
|
||||
<name>board</name>
|
||||
<uri>model://board</uri>
|
||||
<pose>0.45 0.0 0.0 0.0 0.0 0.0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<name>bishop</name>
|
||||
<uri>model://bishop</uri>
|
||||
<pose>0.35 0.0 0.0 0.0 0.0 0.0</pose>
|
||||
</include>
|
||||
</world>
|
||||
</sdf>
|
|
@ -55,29 +55,6 @@
|
|||
<real_time_factor>true</real_time_factor>
|
||||
<iterations>true</iterations>
|
||||
</plugin>
|
||||
<!-- <plugin filename="ImageDisplay" name="Image Display 3">
|
||||
<ignition-gui>
|
||||
<title>RGBD: image</title>
|
||||
<property key="state" type="string">floating</property>
|
||||
<property type="double" key="width">350</property>
|
||||
<property type="double" key="height">315</property>
|
||||
<property type="double" key="y">320</property>
|
||||
</ignition-gui>
|
||||
<topic>rgbd_camera/image</topic>
|
||||
<topic_picker>false</topic_picker>
|
||||
</plugin>
|
||||
<plugin filename="ImageDisplay" name="Image Display 3">
|
||||
<ignition-gui>
|
||||
<title>RGBD: depth</title>
|
||||
<property key="state" type="string">floating</property>
|
||||
<property type="double" key="width">350</property>
|
||||
<property type="double" key="height">315</property>
|
||||
<property type="double" key="x">500</property>
|
||||
<property type="double" key="y">320</property>
|
||||
</ignition-gui>
|
||||
<topic>rgbd_camera/depth_image</topic>
|
||||
<topic_picker>false</topic_picker>
|
||||
</plugin> -->
|
||||
</gui>
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
|
@ -117,247 +94,46 @@
|
|||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
<model name='rack'>
|
||||
<pose>0 0.7 0 0 0 0</pose>
|
||||
<static>1</static>
|
||||
<link name='body'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.35 0.35 0.35</scale>
|
||||
<uri>model://rack/model/rack.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>0.35 0.35 0.35</scale>
|
||||
<uri>model://rack/model/rack.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<self_collide>0</self_collide>
|
||||
<enable_wind>0</enable_wind>
|
||||
<kinematic>0</kinematic>
|
||||
</link>
|
||||
</model>
|
||||
<model name='table'>
|
||||
<pose>-0.75 0 0.2 0 0 0</pose>
|
||||
<static>1</static>
|
||||
<link name='telo'>
|
||||
<visual name='visual'>
|
||||
<geometry>
|
||||
<!-- <mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://table/model/table.dae</uri>
|
||||
</mesh> -->
|
||||
<box>
|
||||
<size>0.8 0.8 0.4</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<!-- <mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>model://table/model/table.stl</uri>
|
||||
</mesh> -->
|
||||
<box>
|
||||
<size>0.8 0.8 0.4</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<max_contacts>10</max_contacts>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode/>
|
||||
</contact>
|
||||
<bounce/>
|
||||
<friction>
|
||||
<torsional>
|
||||
<ode/>
|
||||
</torsional>
|
||||
<ode/>
|
||||
</friction>
|
||||
</surface>
|
||||
</collision>
|
||||
<self_collide>0</self_collide>
|
||||
<enable_wind>0</enable_wind>
|
||||
<kinematic>0</kinematic>
|
||||
</link>
|
||||
</model>
|
||||
<!-- Manipulating objects -->
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box1</name>
|
||||
<pose>0.25 0.65 0.6515 0 0 0</pose>
|
||||
<pose>0.25 0.65 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box2</name>
|
||||
<pose>0 0.65 0.6515 0 0 0</pose>
|
||||
<pose>0 0.65 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box3</name>
|
||||
<pose>-0.25 0.65 0.6515 0 0 0</pose>
|
||||
<pose>-0.25 0.65 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box4</name>
|
||||
<pose>0.25 0.65 0.3015 0 0 0</pose>
|
||||
<pose>0.25 0.75 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box5</name>
|
||||
<pose>0 0.65 0.3015 0 0 0</pose>
|
||||
<pose>0 0.75 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>box6</name>
|
||||
<pose>-0.25 0.65 0.3015 0 0 0</pose>
|
||||
</include>
|
||||
<pose>-0.25 0.75 0.025 0 0 0</pose>
|
||||
</include>
|
||||
<!-- <include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid1</name>
|
||||
<pose>-0.9000 -0.05 0.5250 0 0 0</pose>
|
||||
<uri>model://fork</uri>
|
||||
<name>fork_gt</name>
|
||||
<pose>1.5 0.3 0.25 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid2</name>
|
||||
<pose>-0.9000 0.0 0.5250 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid3</name>
|
||||
<pose>-0.9000 0.05 0.5250 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid4</name>
|
||||
<pose>-0.9 -0.0243 0.5750 0 -0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid5</name>
|
||||
<pose>-0.9 0.0260 0.5750 0 -0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>model://box1</uri>
|
||||
<name>pyramid6</name>
|
||||
<pose>-0.9 0 0.6250 0 0 0</pose>
|
||||
</include> -->
|
||||
|
||||
<!-- <model name="camera">
|
||||
<static>1</static>
|
||||
<pose>-2.0 -0.55 1.44 0 0.44 0.44</pose>
|
||||
<link name="link">
|
||||
<pose>0.05 0.05 0.05 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.000166667</ixx>
|
||||
<iyy>0.000166667</iyy>
|
||||
<izz>0.000166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.1 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.1 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="camera" type="camera">
|
||||
<camera>
|
||||
<horizontal_fov>1.047</horizontal_fov>
|
||||
<image>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>100</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>30</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>camera</topic>
|
||||
</sensor>
|
||||
</link>
|
||||
</model> -->
|
||||
|
||||
<!-- <model name="rgbd_camera">
|
||||
<static>1</static>
|
||||
<pose>0 0.3 0.7 0 0.0 1.57</pose>
|
||||
<link name="link">
|
||||
<pose>0.0 0.0 0.0 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.1</mass>
|
||||
<inertia>
|
||||
<ixx>0.000166667</ixx>
|
||||
<iyy>0.000166667</iyy>
|
||||
<izz>0.000166667</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.1 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.1 0.1 0.1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="rgbd_camera" type="rgbd_camera">
|
||||
<camera>
|
||||
<horizontal_fov>1.047</horizontal_fov>
|
||||
<image>
|
||||
<width>320</width>
|
||||
<height>240</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>100</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>30</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>rgbd_camera</topic>
|
||||
<enable_metrics>true</enable_metrics>
|
||||
</sensor>
|
||||
</link>
|
||||
</model> -->
|
||||
<!-->
|
||||
<uri>model://king</uri>
|
||||
<name>king1</name>
|
||||
<pose>1.5 0.2 0.25 0 0 0</pose>
|
||||
</-->
|
||||
</world>
|
||||
</sdf>
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue