Skip to content

Commit

Permalink
Almost finalized config
Browse files Browse the repository at this point in the history
  • Loading branch information
davidcalderon03 committed Jul 30, 2023
1 parent 6a17b90 commit 111d9fc
Show file tree
Hide file tree
Showing 2 changed files with 97 additions and 11 deletions.
1 change: 0 additions & 1 deletion urc_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,6 @@ install(
launch
urdf
config
rviz
src
DESTINATION share/${PROJECT_NAME}/
)
Expand Down
107 changes: 97 additions & 10 deletions urc_gazebo/urdf/walli.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -59,12 +59,12 @@
<material>Gazebo/Black</material>
</gazebo>
</xacro:macro>
<xacro:wheel prefix="left_front_wheel" x_reflect="1" y_reflect="-1"/>
<xacro:wheel prefix="left_center_wheel" x_reflect="0" y_reflect="-1"/>
<xacro:wheel prefix="left_rear_wheel" x_reflect="-1" y_reflect="-1"/>
<xacro:wheel prefix="right_front_wheel" x_reflect="1" y_reflect="1"/>
<xacro:wheel prefix="right_center_wheel" x_reflect="0" y_reflect="1"/>
<xacro:wheel prefix="right_rear_wheel" x_reflect="-1" y_reflect="1"/>
<xacro:wheel prefix="left_front_wheel" x_reflect="1" y_reflect="1"/>
<xacro:wheel prefix="left_center_wheel" x_reflect="0" y_reflect="1"/>
<xacro:wheel prefix="left_rear_wheel" x_reflect="-1" y_reflect="1"/>
<xacro:wheel prefix="right_front_wheel" x_reflect="1" y_reflect="-1"/>
<xacro:wheel prefix="right_center_wheel" x_reflect="0" y_reflect="-1"/>
<xacro:wheel prefix="right_rear_wheel" x_reflect="-1" y_reflect="-1"/>

<!-- Robot Footprint -->
<link name="base_footprint"/>
Expand Down Expand Up @@ -252,11 +252,11 @@
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<origin xyz="0.0 0.0 0.1" rpy="0.0 0.0 0.0"/>
</joint>
<xacro:VLP-16 parent="lidar_link" name="lidar" topic="/scan" hz="${lidar_hz}" samples="${lidar_samples}" gpu="false">
<!-- <xacro:VLP-16 parent="lidar_link" name="lidar" topic="/scan" hz="${lidar_hz}" samples="${lidar_samples}" gpu="false">
<origin xyz="${lidar_x} 0.0 ${lidar_z}" rpy="0 ${lidar_pitch} 0" />
</xacro:VLP-16>
</xacro:VLP-16> -->
<gazebo reference="lidar_link">
<sensor name="lidar" type="ray">
<always_on>true</always_on>
Expand All @@ -272,7 +272,7 @@
</horizontal>
</scan>
<range>
<min>0.120000</min>
<min>0.12</min>
<max>3.5</max>
<resolution>0.015000</resolution>
</range>
Expand Down Expand Up @@ -353,6 +353,93 @@
<xacro:camera orientation="center" origin_x="0.15" origin_y="0" origin_z="-0.1" yaw="-0.14"/>
<xacro:camera orientation="left" origin_x="0" origin_y="0.1" origin_z="0" yaw="1.5"/>
<xacro:camera orientation="right" origin_x="0" origin_y="-0.1" origin_z="0" yaw="-1.5"/>


<!-- Depth Camera (addition for Nav2) -->
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.015 0.130 0.022"/>
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.015 0.130 0.022"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.035"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001" />
</inertial>
</link>

<joint name="camera_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0.215 0 0.05" rpy="0 0 0"/>
</joint>

<link name="camera_depth_frame"/>

<joint name="camera_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
<parent link="camera_link"/>
<child link="camera_depth_frame"/>
</joint>

<gazebo reference="camera_link">
<sensor name="depth_camera" type="depth">
<visualize>true</visualize>
<update_rate>30.0</update_rate>
<camera name="camera">
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
</camera>
<plugin name="depth_camera_controller" filename="libgazebo_ros_camera.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<frame_name>camera_depth_frame</frame_name>
<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>3.0</pointCloudCutoffMax>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>
<distortionK3>0</distortionK3>
<distortionT1>0</distortionT1>
<distortionT2>0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>













<gazebo>
<sensor name="imu" type="imu">
Expand Down

0 comments on commit 111d9fc

Please sign in to comment.