Added first version of Sensorsim

This commit is contained in:
wittenator
2023-11-29 23:09:05 +01:00
parent 784dca286b
commit 97443604b7
15 changed files with 1028 additions and 0 deletions

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,52 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<joint name="camera_joint" type="fixed">
<parent link="laser_frame"/>
<child link="camera_link"/>
<origin xyz="0 -0.2 0" rpy="0 0 0"/>
</joint>
<link name="camera_link">
<visual>
<geometry>
<box size="0.025 0.09 0.025"/>
</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="segmentation_camera" type="segmentation_camera">
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<topic>semantic</topic>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.01</near>
<far>60</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>20</update_rate>
<visualize>false</visualize>
</sensor>
</gazebo>
</robot>

34
description/colours.xacro Normal file
View File

@ -0,0 +1,34 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<material name="orange">
<color rgba="1 0.3 0.1 1"/>
</material>
<material name="blue">
<color rgba="0.2 0.2 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
<material name="gray">
<color rgba="0.753 0.753 0.753 1"/>
</material>
<material name="grey">
<color rgba="0.753 0.753 0.753 1"/>
</material>
<material name="silver">
<color rgba="0.88 0.88 0.88 1"/>
</material>
</robot>

View File

@ -0,0 +1,77 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<!-- These make use of xacro's mathematical functionality -->
<xacro:macro name="inertial_sphere" params="mass radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0"
iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0"
izz="${(2/5) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_box" params="mass x y z *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
izz="${(1/12) * mass * (x*x+y*y)}" />
</inertial>
</xacro:macro>
<xacro:macro name="inertial_cylinder" params="mass length radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0"
izz="${(1/2) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>
<!-- Math constants -->
<xacro:property name="math_pi" value="3.141592653589793" />
<xacro:property name="math_pi_over_2" value="1.5707963267948966" />
<xacro:property name="math_pi_over_4" value="0.785398163397448" />
<!-- Inertial for solid cuboid with dimensions x y z -->
<xacro:macro name="solid_cuboid_inertial" params="rpy xyz mass x y z">
<inertial>
<origin rpy="${rpy}" xyz="${xyz}"/>
<mass value="${mass}" />
<inertia
ixx="${mass * (y * y + z * z) / 12.0}" ixy="0.0" ixz="0.0"
iyy="${mass * (x * x + z * z) / 12.0}" iyz="0.0"
izz="${mass * (x * x + y * y) / 12.0}" />
</inertial>
</xacro:macro>
<!-- Inertial for solid cylinder with radius and length aligned to z-axis -->
<xacro:macro name="solid_cylinder_inertial" params="rpy xyz mass radius length">
<inertial>
<origin rpy="${rpy}" xyz="${xyz}"/>
<mass value="${mass}" />
<inertia
ixx="${mass * (3.0 * radius * radius + length * length) / 12.0}" ixy="0.0" ixz="0.0"
iyy="${mass * (3.0 * radius * radius + length * length) / 12.0}" iyz="0.0"
izz="${mass * (radius * radius) / 2.0}" />
</inertial>
</xacro:macro>
<!-- A null inertial - used in placeholder links to esure the model will work in Gazebo -->
<xacro:macro name="null_inertial">
<inertial>
<mass value="0.001"/>
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
</xacro:macro>
</robot>

67
description/lidar.xacro Normal file
View File

@ -0,0 +1,67 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:include filename="inertial_macros.xacro"/>
<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="-1.1 0.0 1.0" rpy="0 0 0"/>
</joint>
<link name="laser_frame">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
</geometry>
<material name="red"/>
</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/Red</material>
<sensor name='gpu_lidar' type='gpu_lidar'>
<topic>lidar</topic>
<update_rate>5</update_rate>
<ignition_frame_id>laser_frame</ignition_frame_id>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>${-90*deg_to_rad}</min_angle>
<max_angle>${90*deg_to_rad}</max_angle>
</horizontal>
<vertical>
<samples>64</samples>
<resolution>1</resolution>
<min_angle>${-45*deg_to_rad}</min_angle>
<max_angle>${0*deg_to_rad}</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>60.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<alwaysOn>true</alwaysOn>
</sensor>
</gazebo>
</robot>

View File

@ -0,0 +1,24 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="sensor_sim">
<!-- Define parameters-->
<xacro:arg name="lidar_vertical_fov_upper" default="45"/>
<xacro:arg name="lidar_vertical_fov_lower" default="-45"/>
<xacro:arg name="lidar_horizontal_fov_upper" default="60"/>
<xacro:arg name="lidar_horizontal_fov_lower" default="-60"/>
<!-- Math constants -->
<xacro:property name="deg_to_rad" value="0.01745329251994329577"/>
<!-- Include the colours -->
<xacro:include filename="colours.xacro" />
<!-- Include the inertial macros -->
<xacro:include filename="inertial_macros.xacro"/>
<xacro:include filename="robot_core.xacro" />
<xacro:include filename="bbox_camera.xacro" />
<xacro:include filename="lidar.xacro" />
</robot>

View File

@ -0,0 +1,45 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link">
</link>
<!-- CHASSIS LINK -->
<joint name="chassis_joint" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
</joint>
<link name="chassis">
<visual>
<geometry>
<mesh filename="file://$(find sensor_sim)/description/assets/ft24_asm.dae"/>
</geometry>
<material name="grey"/>
</visual>
<collision>
<geometry>
<box size="2.0 2.0 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="1.0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<gazebo reference="chassis">
<material>Gazebo/White</material>
<visual>
<laser_retro>255</laser_retro>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>10</label>
</plugin>
</visual>
</gazebo>
</robot>