Skip to content
Merged
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
6 changes: 3 additions & 3 deletions src/description/urdf/athena_drive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -49,9 +49,9 @@
</xacro:gps_sensor>

<xacro:ground_truth_odometry robot_base_frame="base_footprint"/>

<xacro:depth_camera parent_link="base_link">
<origin xyz="0.75 0 -0.37" rpy="0 0 0"/>
<xacro:depth_camera parent="base_footprint">
<origin xyz="0.0 0.0 0.1" rpy="0 0 0"/>
</xacro:depth_camera>

<xacro:if value="$(arg use_mock_hardware)">
Expand Down
23 changes: 10 additions & 13 deletions src/description/urdf/depth_camera.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="depth_camera" params="parent_link *origin">
<xacro:macro name="depth_camera" params="parent *origin">
<link name="depth_camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -18,20 +18,13 @@
<box size="0.025 0.09 0.025"/>
</geometry>
</collision>
<inertial>
<mass value="0.072"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.00001" ixy="0.0" ixz="0.0"
iyy="0.00001" iyz="0.0"
izz="0.00001"/>
</inertial>
</link>

<link name="depth_camera_optical_frame"/>

<joint name="depth_camera_joint" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent_link}"/>
<parent link="${parent}"/>
<child link="depth_camera_link"/>
</joint>

Expand All @@ -42,12 +35,13 @@
</joint>

<gazebo reference="depth_camera_link">
<sensor name="depth_camera" type="depth_camera">
<sensor name="depth_camera" type="depth">
<always_on>1</always_on>
<update_rate>30</update_rate>
<update_rate>10</update_rate>
<visualize>true</visualize>
<topic>depth_camera</topic>
<camera name="depth_camera">
<horizontal_fov>1.047198</horizontal_fov>
<horizontal_fov>1.05</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
Expand All @@ -57,8 +51,11 @@
<near>0.1</near>
<far>10.0</far>
</clip>
<depth_camera>
<output>points</output>
</depth_camera>
</camera>
<plugin filename="libgz-sim-sensors-system.so" name="gz::sim::systems::Sensors">
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
</sensor>
Expand Down
4 changes: 2 additions & 2 deletions src/simulation/launch/bridge.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ def generate_launch_description():
name='depth_camera_bridge',
output='screen',
arguments=[
'/depth_camera@sensor_msgs/msg/Image[ignition.msgs.Image',
'/depth_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked',
'/depth_camera@sensor_msgs/msg/Image@gz.msgs.Image',
'/depth_camera/points@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked',
],
),

Expand Down
10 changes: 8 additions & 2 deletions src/simulation/launch/bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,19 @@
choices=['true', 'false'],
description='Publish ground truth odom -> base_link transform'
),
DeclareLaunchArgument(
'rqt',
default_value='false',
choices=['true', 'false'],
description='Open RQt.'
),
]

def generate_launch_description():
pkg_sim = get_package_share_directory('simulation')

gazebo_launch = PathJoinSubstitution(
[pkg_sim, 'launch', 'gz_sim.launch.py'])
[pkg_sim, 'launch', 'gz_sim.launch.py'])
robot_spawn_launch = PathJoinSubstitution(
[pkg_sim, 'launch', 'spawn.launch.py'])
bridge_launch = PathJoinSubstitution(
Expand Down Expand Up @@ -93,4 +99,4 @@ def generate_launch_description():
ld.add_action(bridge)
ld.add_action(control)
ld.add_action(ground_truth_tf)
return ld
return ld
18 changes: 16 additions & 2 deletions src/simulation/launch/spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,16 @@
DeclareLaunchArgument('rviz', default_value='false',
choices=['true', 'false'],
description='Start rviz.'),
DeclareLaunchArgument('rqt', default_value='false',
description='Open RQt.'),
DeclareLaunchArgument('image_topic', default_value='/depth_camera',
description='Topic to start viewing in RQt.'),
DeclareLaunchArgument('use_sim_time', default_value='true',
choices=['true', 'false'],
description='use_sim_time'),
DeclareLaunchArgument('namespace', default_value='',
description='Robot namespace'),


]

Expand Down Expand Up @@ -70,10 +75,19 @@ def generate_launch_description():
executable='rviz2',
name='rviz2',
output='screen',
condition=conditions.IfCondition(LaunchConfiguration('rviz'))
condition=conditions.IfCondition(LaunchConfiguration('rviz')),
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}]
),

Node(
package='rqt_image_view',
executable='rqt_image_view',
name='rqt',
arguments=[LaunchConfiguration('image_topic')],
condition=conditions.IfCondition(LaunchConfiguration('rqt'))
),
])

ld = LaunchDescription(ARGUMENTS)
ld.add_action(spawn_robot_group_action)
return ld
return ld