Skip to content
Snippets Groups Projects
Commit 081899ed authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Updated the dynamic parameters of the model. Still more tunning is required.

Used custom gazebo plugin configuration files for each of the sensors.
parent bfde99e8
No related branches found
No related tags found
No related merge requests found
......@@ -37,7 +37,9 @@
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>model_car</robotNamespace>
<robotNamespace>/model_car</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
......
......@@ -3,11 +3,19 @@
<robot name="model_car" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find model_car_description)/urdf/include/wheel.xacro" />
<xacro:include filename="$(find model_car_description)/urdf/include/platform.gazebo" />
<xacro:property name="PI" value="3.1415926535897931" />
<xacro:property name="angle_limit" value="${PI/3.0}" />
<link name="base_link">
<inertial>
<mass value="0.001" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx="0.00000001" ixy="0.00000000" ixz="0.0"
iyy="0.00000001" iyz="0.00000000"
izz="0.00000001" />
</inertial>
</link>
<link name="body">
......@@ -51,6 +59,13 @@
</xacro:wheel>
<link name="steer_left">
<inertial>
<mass value="0.001" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx="0.00000001" ixy="0.00000000" ixz="0.0"
iyy="0.00000001" iyz="0.00000000"
izz="0.00000001" />
</inertial>
</link>
<joint name="base_link_2_steer_left_joint" type="revolute">
......@@ -59,7 +74,7 @@
<anchor xyz="0 0 0" />
<parent link="base_link" />
<child link="steer_left" />
<limit lower="-${angle_limit}" upper="${angle_limit}" effort="9.6" velocity="5.3"/>
<limit lower="-${angle_limit}" upper="${angle_limit}" effort="1" velocity="1"/>
<dynamics damping="0.2"/>
</joint>
......@@ -80,6 +95,13 @@
</xacro:wheel>
<link name="steer_right">
<inertial>
<mass value="0.001" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx="0.00000001" ixy="0.00000000" ixz="0.0"
iyy="0.00000001" iyz="0.00000000"
izz="0.00000001" />
</inertial>
</link>
<joint name="base_link_2_steer_right_joint" type="revolute">
......
......@@ -10,39 +10,39 @@
<xacro:property name="PI" value="3.1415926535897931" />
<xacro:rplidar_laser2d name="front_lidar" prefix="model_car" parent="base_link">
<xacro:rplidar_laser2d name="front_lidar" prefix="model_car" parent="base_link" config_file="$(find model_car_gazebo)/config/rp_lidar_config.yaml">
<origin xyz="0.439 0.0 0.05" rpy="0 ${PI} ${PI}" />
</xacro:rplidar_laser2d>
<xacro:hcsr04_sonar name="side_left" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
<xacro:hcsr04_sonar name="side_left" parent="base_link" sim_config="$(find model_car_gazebo)/config/side_left_sonar_config.yaml">
<origin xyz="0.2585 0.1107 0.0" rpy="-${PI/2.0} ${PI/2.0} 0" />
</xacro:hcsr04_sonar>
<xacro:hcsr04_sonar name="side_right" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
<xacro:hcsr04_sonar name="side_right" parent="base_link" sim_config="$(find model_car_gazebo)/config/side_right_sonar_config.yaml">
<origin xyz="0.2585 -0.1107 0.0" rpy="${PI/2.0} ${PI/2.0} 0" />
</xacro:hcsr04_sonar>
<xacro:hcsr04_sonar name="rear_center" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
<xacro:hcsr04_sonar name="rear_center" parent="base_link" sim_config="$(find model_car_gazebo)/config/rear_center_sonar_config.yaml">
<origin xyz="-0.0882 0.0 0.0" rpy="${PI} ${PI/2.0} 0" />
</xacro:hcsr04_sonar>
<xacro:hcsr04_sonar name="rear_left" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
<xacro:hcsr04_sonar name="rear_left" parent="base_link" sim_config="$(find model_car_gazebo)/config/rear_left_sonar_config.yaml">
<origin xyz="-0.07912 0.09898 0.0" rpy="${PI+PI/6.0} ${PI/2.0} 0" />
</xacro:hcsr04_sonar>
<xacro:hcsr04_sonar name="rear_right" parent="base_link" sim_config="$(find iri_ranger1d_gazebo)/config/hc_sr04_sonar_ranger1d_sim_config.yaml">
<xacro:hcsr04_sonar name="rear_right" parent="base_link" sim_config="$(find model_car_gazebo)/config/rear_right_sonar_config.yaml">
<origin xyz="-0.07912 -0.09898 0.0" rpy="${PI-PI/6.0} ${PI/2.0} 0" />
</xacro:hcsr04_sonar>
<xacro:mpu9250_imu name="imu" parent="base_link" sim_config="$(find iri_imu_gazebo)/config/mpu9250_imu_sim_config.yaml">
<xacro:mpu9250_imu name="imu" parent="base_link" sim_config="$(find model_car_gazebo)/config/mpu9250_imu_config.yaml">
<origin xyz="0.006 0.0 0.0271" rpy="0 0 0" />
</xacro:mpu9250_imu>
<xacro:uvc_camera name="front_camera" parent="base_link" resolution="low_res" model="basler" sim_config="$(find iri_camera_gazebo)/config/camera_sim_config.yaml">
<xacro:uvc_camera name="front_camera" parent="base_link" resolution="low_res" model="basler" sim_config="$(find model_car_gazebo)/config/basler_camera_sim_config.yaml">
<origin xyz="0.273 0.0 0.180" rpy="0 0 0" />
</xacro:uvc_camera>
<xacro:uvc_camera name="rear_camera" parent="base_link" resolution="low_res" model="delock" sim_config="$(find iri_camera_gazebo)/config/camera_sim_config.yaml">
<xacro:uvc_camera name="rear_camera" parent="base_link" resolution="low_res" model="delock" sim_config="$(find model_car_gazebo)/config/delock_camera_sim_config.yaml">
<origin xyz="-0.0112 0.0 0.055" rpy="0 0 ${PI}" />
</xacro:uvc_camera>
......
......@@ -14,7 +14,7 @@
<!-- <kd>1.0</kd>-->
</gazebo>
<gazebo reference="${parent}_2_${name}_wheel">
<gazebo reference="${parent}_2_${name}_wheel_joint">
<implicitSpringDamper>true</implicitSpringDamper>
<stopCfm>0.0</stopCfm>
<stopErp>0.0</stopErp>
......
......@@ -30,17 +30,17 @@
</collision>
</link>
<joint name="${parent}_2_${name}_wheel" type="continuous">
<joint name="${parent}_2_${name}_wheel_joint" type="continuous">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_wheel"/>
<axis xyz="0 0 ${direction}"/>
<limit effort="10000" velocity="10.0"/>
<limit effort="5" velocity="1.0"/>
</joint>
<transmission name="${name}_tran">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${parent}_2_${name}_wheel">
<joint name="${parent}_2_${name}_wheel_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_motor">
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment