Skip to content

Commit

Permalink
robot description changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Thiefish committed Dec 22, 2023
1 parent 1ce23b1 commit aa840ea
Show file tree
Hide file tree
Showing 4 changed files with 150 additions and 20 deletions.
62 changes: 62 additions & 0 deletions src/ezbot_descr_simul/description/camera.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

<joint name="camera_joint" type="fixed">
<parent link="chassis"/>
<child link="camera_link"/>
<origin xyz="0.128 0 0.241" rpy="0 0.18 0"/>
</joint>

<link name="camera_link">
<visual>
<geometry>
<box size="0.010 0.03 0.03"/>
</geometry>
<material name="black"/>
</visual>
<visual>
<origin xyz="0 0 -0.05"/>
<geometry>
<cylinder radius="0.002" length="0.1"/>
</geometry>
<material name="black"/>
</visual>
</link>


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

<link name="camera_link_optical"></link>



<gazebo reference="camera_link">
<material>Gazebo/Black</material>

<sensor name="camera" type="camera">
<pose> 0 0 0 0 0 0 </pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<camera>
<horizontal_fov>1.089</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<frame_name>camera_link_optical</frame_name>
</plugin>
</sensor>
</gazebo>

</robot>
66 changes: 66 additions & 0 deletions src/ezbot_descr_simul/description/lidar.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="0.055 0 0.41" rpy="0 0 0"/>
</joint>

<link name="laser_frame">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
<material name="black"/>
</visual>
<visual>
<origin xyz="0 0 -0.05"/>
<geometry>
<cylinder radius="0.01" length="0.1"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>



<gazebo reference="laser_frame">
<material>Gazebo/Black</material>

<sensor name="laser" type="ray">
<pose> 0.055 0 0.03 0 0 0 </pose>
<visualize>false</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>450</samples>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>12</max>
</range>
</ray>
<plugin name="laser_controller" filename="libgazebo_ros_ray_sensor.so">
<ros>
<argument>~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>laser_frame</frame_name>
</plugin>
</sensor>
</gazebo>

</robot>
3 changes: 2 additions & 1 deletion src/ezbot_descr_simul/description/robot.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot">

<xacro:include filename="robot_core.xacro" />

<xacro:include filename="lidar.xacro"/>
<xacro:include filename="gazebo_control.xacro" />
<xacro:include filename="camera.xacro" />

</robot>
39 changes: 20 additions & 19 deletions src/ezbot_descr_simul/description/robot_core.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
</material>

<link name="base_link">

</link>

<!--Chassis-->
Expand All @@ -37,22 +37,23 @@
<origin xyz="-0.1 0 0"/>
</joint>

<!--z=0.06-->
<link name="chassis">
<visual>
<origin xyz="0.055 0 0.03"/>
<origin xyz="0.055 0 0.175"/>
<geometry>
<box size="0.11 0.11 0.06"/>
<box size="0.11 0.11 0.35"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin xyz="0.055 0 0.03"/>
<origin xyz="0.055 0 0.175"/>
<geometry>
<box size="0.11 0.11 0.06"/>
<box size="0.11 0.11 0.35"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.11" y="0.11" z="0.06">
<origin xyz="0.055 0 0.03" rpy="0 0 0"/>
<xacro:inertial_box mass="0.5" x="0.11" y="0.11" z="0.35">
<origin xyz="0.055 0 0.175" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand Down Expand Up @@ -194,14 +195,14 @@
</joint>


<link name='roue_droite'>
<visual>
<link name='roue_droite'>
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<collision>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
Expand All @@ -228,14 +229,14 @@
</joint>


<link name='roue_gauche'>
<visual>
<link name='roue_gauche'>
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<collision>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
Expand All @@ -262,14 +263,14 @@
</joint>


<link name='roue_avant'>
<visual>
<link name='roue_avant'>
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<collision>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
Expand All @@ -296,14 +297,14 @@
</joint>


<link name='roue_arriere'>
<visual>
<link name='roue_arriere'>
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<collision>
<geometry>
<cylinder radius="0.03" length="0.02"/>
</geometry>
Expand Down

0 comments on commit aa840ea

Please sign in to comment.