Skip to content
This repository was archived by the owner on Feb 21, 2021. It is now read-only.
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
368 changes: 261 additions & 107 deletions assets/gazebo/models/f1_redbull/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
<pose>0 0 0 0 0 0</pose>
<static>false</static>
<link name="f1">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>10</mass>
<inertia>
<ixx>1</ixx>
Expand All @@ -14,15 +14,15 @@
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>1.0</izz>
</inertia>
</inertial>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<mesh>
<uri>model://f1_redbull/Redbull/Car.obj</uri>
<scale>0.2 0.2 0.2</scale>
</mesh>
</geometry>
<geometry>
<mesh>
<uri>model://f1_redbull/Redbull/Car.obj</uri>
<scale>0.2 0.2 0.2</scale>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
Expand All @@ -32,106 +32,260 @@
</mesh>
</geometry>
</visual>
</link>
</link>

<link name='camera_top_body_left'>
<pose>0.45000 0.040000 0.1000000 0.000000 -0.000000 0.0000000</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>1.000000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>1.000000</iyy>
<iyz>0.000000</iyz>
<izz>1.000000</izz>
</inertia>
</inertial>
<sensor name='cam_f1_left' type='camera'>
<pose>0.000000 0.000000 0.000000 0.000000 0.00000 0.00000</pose>
<update_rate>20.000000</update_rate>
<camera name='cleft'>
<horizontal_fov>1.570000</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.100000</near>
<far>15.000000</far>
</clip>
</camera>
<plugin name="camera_controller_left" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>F1ROS/cameraL</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_top_body_left</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
<visual name='visual'>
<geometry>
<sphere>
<radius>.005</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.100000 0.100000 0.100000</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.000000</mu>
<mu2>100000.000000</mu2>
<slip1>0.000000</slip1>
<slip2>0.000000</slip2>
</ode>
</friction>
</surface>
<max_contacts>10</max_contacts>
</collision>
<velocity_decay>
<linear>0.000000</linear>
<angular>0.000000</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>

<link name='camera_top_body_right'>
<pose>0.45000 -0.040000 0.1000000 0.000000 -0.000000 0.0000000</pose>
<inertial>
<mass>2</mass>
<inertia>
<ixx>1.000000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>1.000000</iyy>
<iyz>0.000000</iyz>
<izz>1.000000</izz>
</inertia>
</inertial>
<sensor name='cam_f1_right' type='camera'>
<pose>0.000000 0.000000 0.000000 0.000000 0.00000 0.00000</pose>
<update_rate>20.000000</update_rate>
<camera name='cright'>
<horizontal_fov>1.570000</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.100000</near>
<far>15.000000</far>
</clip>
</camera>
<plugin name="camera_controller_right" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>F1ROS/cameraR</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_top_body_right</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
<visual name='visual'>
<geometry>
<sphere>
<radius>.005</radius>
</sphere>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.100000 0.100000 0.100000</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.000000</mu>
<mu2>100000.000000</mu2>
<slip1>0.000000</slip1>
<slip2>0.000000</slip2>
</ode>
</friction>
</surface>
<max_contacts>10</max_contacts>
</collision>
<velocity_decay>
<linear>0.000000</linear>
<angular>0.000000</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>

<link name='laser'>
<pose>0.500000 0.000000 0.072000 0.000000 0.000000 0.00000</pose>
<gravity>0</gravity>
<inertial>
<mass>1</mass>
<inertia>
<ixx>1.000000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>1.000000</iyy>
<iyz>0.000000</iyz>
<izz>1.000000</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://f1ROS/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision-base'>
<pose>0.000000 0.000000 -0.014500 0.000000 0.000000 0.000000</pose>
<geometry>
<box>
<size>0.050000 0.050000 0.041000</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<collision name='collision-top'>
<pose>0.000000 0.000000 0.020500 0.000000 0.000000 0.000000</pose>
<geometry>
<cylinder>
<radius>0.021000</radius>
<length>0.029000</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<sensor name='laser' type='ray'>
<ray>
<scan>
<horizontal>
<samples>180</samples>
<resolution>1.000000</resolution>
<min_angle>-1.570000</min_angle>
<max_angle>1.570000</max_angle>
</horizontal>
</scan>
<range>
<min>0.080000</min>
<max>10.000000</max>
<resolution>0.010000</resolution>
</range>
</ray>
<update_rate>20.000000</update_rate>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/F1ROS/laser/scan</topicName>
<frameName>laser</frameName>
</plugin>
<always_on>1</always_on>
<visualize>1</visualize>
</sensor>
<velocity_decay>
<linear>0.000000</linear>
<angular>0.000000</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>
<pose>0.500000 0.000000 0.072000 0.000000 0.000000 0.00000</pose>
<gravity>0</gravity>
<inertial>
<mass>1</mass>
<inertia>
<ixx>1.000000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>1.000000</iyy>
<iyz>0.000000</iyz>
<izz>1.000000</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://f1ROS/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision-base'>
<pose>0.000000 0.000000 -0.014500 0.000000 0.000000 0.000000</pose>
<geometry>
<box>
<size>0.050000 0.050000 0.041000</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<collision name='collision-top'>
<pose>0.000000 0.000000 0.020500 0.000000 0.000000 0.000000</pose>
<geometry>
<cylinder>
<radius>0.021000</radius>
<length>0.029000</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
</collision>
<sensor name='laser' type='ray'>
<ray>
<scan>
<horizontal>
<samples>180</samples>
<resolution>1.000000</resolution>
<min_angle>-1.570000</min_angle>
<max_angle>1.570000</max_angle>
</horizontal>
</scan>
<range>
<min>0.080000</min>
<max>10.000000</max>
<resolution>0.010000</resolution>
</range>
</ray>
<update_rate>20.000000</update_rate>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/F1ROS/laser/scan</topicName>
<frameName>laser</frameName>
</plugin>
<always_on>0</always_on>
<visualize>0</visualize>
</sensor>
<velocity_decay>
<linear>0.000000</linear>
<angular>0.000000</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
</link>

<joint type="revolute" name="laser_joint">
<pose>0 0 0 0 0 0</pose>
<child>laser</child>
<parent>f1</parent>
<axis>
<xyz>0 0 0</xyz>
</axis>
</joint>

<joint type="revolute" name="camera_left">
<pose>0 0 0 0 0 0</pose>
<child>camera_top_body_left</child>
<parent>f1</parent>
<axis>
<xyz>0 0 0</xyz>
</axis>
</joint>

<joint type="revolute" name="laser_joint">
<pose>0 0 0 0 0 0</pose>
<child>laser</child>
<parent>f1</parent>
<axis>
<xyz>0 0 0</xyz>
</axis>
</joint>
<joint type="revolute" name="camera_right">
<pose>0 0 0 0 0 0</pose>
<child>camera_top_body_right</child>
<parent>f1</parent>
<axis>
<xyz>0 0 0</xyz>
</axis>
</joint>

<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
<commandTopic>F1ROS/cmd_vel</commandTopic>
Expand Down
Binary file not shown.
Loading