update poses, add camera to urdf and add bridge
This commit is contained in:
parent
73d3c61b8b
commit
4371dbdcee
3 changed files with 25 additions and 243 deletions
|
@ -45,7 +45,7 @@ def generate_launch_description():
|
|||
declared_arguments.append(
|
||||
DeclareLaunchArgument(
|
||||
"controllers_file",
|
||||
default_value="ur_controllers.yaml",
|
||||
default_value="ur_plus_gripper_controllers.yaml",
|
||||
description="YAML file with the controllers configuration.",
|
||||
)
|
||||
)
|
||||
|
|
|
@ -68,11 +68,27 @@ def generate_launch_description():
|
|||
executable="env_manager_node",
|
||||
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',
|
||||
)
|
||||
|
||||
|
||||
|
||||
nodes_to_start = [
|
||||
gazebo,
|
||||
gazebo_server,
|
||||
gazebo_spawn_robot,
|
||||
env_manager
|
||||
env_manager,
|
||||
rgbd_bridge_out
|
||||
]
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
||||
|
|
|
@ -54,29 +54,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>
|
||||
|
@ -116,247 +93,36 @@
|
|||
</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>
|
||||
<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>
|
||||
</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> -->
|
||||
</world>
|
||||
</sdf>
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue