Added synchronisation between camera and data collection

This commit is contained in:
wittenator
2024-03-18 17:07:34 +01:00
parent 5af2dd40fb
commit 5ae995ec36
5 changed files with 98 additions and 97 deletions

View File

@ -4,7 +4,7 @@
<joint name="camera_joint" type="fixed">
<parent link="chassis"/>
<child link="camera_link"/>
<origin xyz="-0.996 0.0696 1.04" rpy="${11.8*deg_to_rad} ${20.2*deg_to_rad} ${22.5*deg_to_rad}"/>
<origin xyz="-1.0269530 0.0328365 0.9993990" rpy="0 ${9.0*deg_to_rad} ${-20.1931*deg_to_rad}"/>
</joint>
<link name="camera_link">
@ -45,7 +45,7 @@
</clip>
</camera>
<always_on>1</always_on>
<update_rate>20</update_rate>
<update_rate>3</update_rate>
<visualize>false</visualize>
</sensor>
<sensor name="boundingbox_camera" type="boundingbox_camera">
@ -65,7 +65,7 @@
</clip>
</camera>
<always_on>1</always_on>
<update_rate>20</update_rate>
<update_rate>3</update_rate>
<visualize>false</visualize>
</sensor>
</gazebo>

View File

@ -6,20 +6,20 @@
<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="-0.985 0.0 ${1.08-0.024604}" rpy="0 0 0"/>
<origin xyz="-0.994175 0.0 1.0387512" rpy="0 ${9.0*deg_to_rad} 0"/>
</joint>
<link name="laser_frame">
<visual>
<geometry>
<cylinder radius="0.05" length="0.04"/>
<box size="0.105 0.1316 0.065"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.04"/>
<box size="0.105 0.1316 0.065"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
@ -38,16 +38,16 @@
<ray>
<scan>
<horizontal>
<samples>640</samples>
<samples>666</samples>
<resolution>1</resolution>
<min_angle>${-90*deg_to_rad}</min_angle>
<max_angle>${90*deg_to_rad}</max_angle>
<min_angle>${-60*deg_to_rad}</min_angle>
<max_angle>${60*deg_to_rad}</max_angle>
</horizontal>
<vertical>
<samples>64</samples>
<samples>108</samples>
<resolution>1</resolution>
<min_angle>${-45*deg_to_rad}</min_angle>
<max_angle>${0*deg_to_rad}</max_angle>
<min_angle>${-12.5*deg_to_rad}</min_angle>
<max_angle>${12.5*deg_to_rad}</max_angle>
</vertical>
</scan>
<range>
@ -63,5 +63,10 @@
</ray>
<alwaysOn>true</alwaysOn>
</sensor>
<visual>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>30</label>
</plugin>
</visual>
</gazebo>
</robot>

View File

@ -30,6 +30,11 @@
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<gazebo>
<static>true</static>
</gazebo>
</link>
<gazebo reference="chassis">