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

Improved the dynamic model of the car. Still not good enough.

parent 081899ed
No related branches found
No related tags found
No related merge requests found
...@@ -5,6 +5,7 @@ Panels: ...@@ -5,6 +5,7 @@ Panels:
Property Tree Widget: Property Tree Widget:
Expanded: Expanded:
- /Global Options1 - /Global Options1
- /RobotModel1
Splitter Ratio: 0.625 Splitter Ratio: 0.625
Tree Height: 841 Tree Height: 841
- Class: rviz/Selection - Class: rviz/Selection
...@@ -63,7 +64,7 @@ Visualization Manager: ...@@ -63,7 +64,7 @@ Visualization Manager:
{} {}
Update Interval: 0 Update Interval: 0
Value: false Value: false
- Alpha: 0.899999976 - Alpha: 1
Class: rviz/RobotModel Class: rviz/RobotModel
Collision Enabled: false Collision Enabled: false
Enabled: true Enabled: true
...@@ -511,9 +512,9 @@ Visualization Manager: ...@@ -511,9 +512,9 @@ Visualization Manager:
Enabled: true Enabled: true
Invert Rainbow: false Invert Rainbow: false
Max Color: 255; 255; 255 Max Color: 255; 255; 255
Max Intensity: 8.40779079e-45 Max Intensity: 999999
Min Color: 0; 0; 0 Min Color: 0; 0; 0
Min Intensity: 1.40129846e-45 Min Intensity: 8.40779079e-45
Name: RP_Lidar Name: RP_Lidar
Position Transformer: XYZ Position Transformer: XYZ
Queue Size: 10 Queue Size: 10
...@@ -553,25 +554,25 @@ Visualization Manager: ...@@ -553,25 +554,25 @@ Visualization Manager:
Views: Views:
Current: Current:
Class: rviz/Orbit Class: rviz/Orbit
Distance: 6.36128855 Distance: 1.55903006
Enable Stereo Rendering: Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987 Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1 Stereo Focal Distance: 1
Swap Stereo Eyes: false Swap Stereo Eyes: false
Value: false Value: false
Focal Point: Focal Point:
X: 0.408853233 X: 0.744714677
Y: -0.595593214 Y: -0.03747968
Z: -0.697179675 Z: 0.0418403521
Focal Shape Fixed Size: false Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007 Focal Shape Size: 0.0500000007
Invert Z Axis: false Invert Z Axis: false
Name: Current View Name: Current View
Near Clip Distance: 0.00999999978 Near Clip Distance: 0.00999999978
Pitch: 0.714797616 Pitch: 0.224798039
Target Frame: base_link Target Frame: base_link
Value: Orbit (rviz) Value: Orbit (rviz)
Yaw: 3.99539614 Yaw: 3.58039188
Saved: ~ Saved: ~
Window Geometry: Window Geometry:
Displays: Displays:
......
...@@ -7,32 +7,36 @@ ...@@ -7,32 +7,36 @@
<gazebo reference="body"> <gazebo reference="body">
<material>Gazebo/Grey</material> <material>Gazebo/Grey</material>
<gravity>true</gravity> <gravity>true</gravity>
<self_collide>false</self_collide> <selfCollide>true</selfCollide>
<dampingFactor>0.0002</dampingFactor> <!-- <dampingFactor>0.0002</dampingFactor> -->
<mu1>0.300000</mu1> <!-- <mu1>0.300000</mu1> -->
<mu2>1.000000</mu2> <!-- <mu2>1.000000</mu2> -->
<!-- <kp>50000000.0</kp>--> <!-- <kp>50000000.0</kp> -->
<!-- <kd>1.0</kd>--> <!-- <kd>1.0</kd> -->
</gazebo> </gazebo>
<gazebo reference="steer_left"> <gazebo reference="steer_left">
<material>Gazebo/Black</material> <material>Gazebo/Black</material>
<gravity>true</gravity>
<dampingFactor>0.2</dampingFactor>
</gazebo> </gazebo>
<gazebo reference="steer_right"> <gazebo reference="steer_right">
<material>Gazebo/Black</material> <material>Gazebo/Black</material>
<gravity>true</gravity>
<dampingFactor>0.2</dampingFactor>
</gazebo> </gazebo>
<gazebo reference="base_link_2_steer_left_joint"> <gazebo reference="base_link_2_steer_left_joint">
<implicitSpringDamper>true</implicitSpringDamper> <implicitSpringDamper>true</implicitSpringDamper>
<stopCfm>0.0</stopCfm> <!-- <stopCfm>0.0</stopCfm> -->
<stopErp>0.0</stopErp> <!-- <stopErp>0.0</stopErp> -->
</gazebo> </gazebo>
<gazebo reference="base_link_2_steer_right_joint"> <gazebo reference="base_link_2_steer_right_joint">
<implicitSpringDamper>true</implicitSpringDamper> <implicitSpringDamper>true</implicitSpringDamper>
<stopCfm>0.0</stopCfm> <!-- <stopCfm>0.0</stopCfm> -->
<stopErp>0.0</stopErp> <!-- <stopErp>0.0</stopErp> -->
</gazebo> </gazebo>
<gazebo> <gazebo>
...@@ -40,6 +44,7 @@ ...@@ -40,6 +44,7 @@
<robotNamespace>/model_car</robotNamespace> <robotNamespace>/model_car</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS> <legacyModeNS>true</legacyModeNS>
<controlPeriod>0.02</controlPeriod>
</plugin> </plugin>
</gazebo> </gazebo>
......
...@@ -60,11 +60,11 @@ ...@@ -60,11 +60,11 @@
<link name="steer_left"> <link name="steer_left">
<inertial> <inertial>
<mass value="0.001" /> <mass value="0.25918139" />
<origin xyz="0.0 0.0 0.0" /> <origin xyz="0.00000000 0.00000000 0.00000000" rpy="0 0 0"/>
<inertia ixx="0.00000001" ixy="0.00000000" ixz="0.0" <inertia ixx="0.00018551" ixy="0.00000000" ixz="0.00000000"
iyy="0.00000001" iyz="0.00000000" iyy="0.00018551" iyz="0.00000000"
izz="0.00000001" /> izz="0.00032398" />
</inertial> </inertial>
</link> </link>
...@@ -74,8 +74,8 @@ ...@@ -74,8 +74,8 @@
<anchor xyz="0 0 0" /> <anchor xyz="0 0 0" />
<parent link="base_link" /> <parent link="base_link" />
<child link="steer_left" /> <child link="steer_left" />
<limit lower="-${angle_limit}" upper="${angle_limit}" effort="1" velocity="1"/> <limit lower="-${angle_limit}" upper="${angle_limit}" effort="0.7" velocity="10.0"/>
<dynamics damping="0.2"/> <dynamics damping="0.7"/>
</joint> </joint>
<transmission name="tran_steer_left"> <transmission name="tran_steer_left">
...@@ -96,11 +96,11 @@ ...@@ -96,11 +96,11 @@
<link name="steer_right"> <link name="steer_right">
<inertial> <inertial>
<mass value="0.001" /> <mass value="0.25918139" />
<origin xyz="0.0 0.0 0.0" /> <origin xyz="0.00000000 0.00000000 0.00000000" rpy="0 0 0"/>
<inertia ixx="0.00000001" ixy="0.00000000" ixz="0.0" <inertia ixx="0.00018551" ixy="0.00000000" ixz="0.00000000"
iyy="0.00000001" iyz="0.00000000" iyy="0.00018551" iyz="0.00000000"
izz="0.00000001" /> izz="0.00032398" />
</inertial> </inertial>
</link> </link>
...@@ -110,8 +110,8 @@ ...@@ -110,8 +110,8 @@
<anchor xyz="0 0 0" /> <anchor xyz="0 0 0" />
<parent link="base_link" /> <parent link="base_link" />
<child link="steer_right" /> <child link="steer_right" />
<limit lower="-${angle_limit}" upper="${angle_limit}" effort="9.6" velocity="5.3"/> <limit lower="-${angle_limit}" upper="${angle_limit}" effort="0.7" velocity="10.0"/>
<dynamics damping="0.2"/> <dynamics damping="0.7"/>
</joint> </joint>
<transmission name="tran_steer_right"> <transmission name="tran_steer_right">
......
...@@ -4,20 +4,20 @@ ...@@ -4,20 +4,20 @@
<xacro:macro name="wheel_gazebo" params=" name"> <xacro:macro name="wheel_gazebo" params=" name">
<gazebo reference="${name}_wheel"> <gazebo reference="${name}_wheel">
<gravity>true</gravity>
<self_collide>false</self_collide>
<material>Gazebo/Black</material> <material>Gazebo/Black</material>
<dampingFactor>0.0002</dampingFactor> <maxContacts>2</maxContacts>
<mu1>0.300000</mu1> <gravity>true</gravity>
<mu2>1.000000</mu2> <selfCollide>true</selfCollide>
<!-- <kp>50000000.0</kp>--> <mu1>100.000000</mu1>
<!-- <kd>1.0</kd>--> <mu2>50.000000</mu2>
<kp>1e15</kp>
<kd>1e13</kd>
</gazebo> </gazebo>
<gazebo reference="${parent}_2_${name}_wheel_joint"> <gazebo reference="${parent}_2_${name}_wheel_joint">
<implicitSpringDamper>true</implicitSpringDamper> <implicitSpringDamper>true</implicitSpringDamper>
<stopCfm>0.0</stopCfm> <!-- <stopCfm>0.0</stopCfm> -->
<stopErp>0.0</stopErp> <!-- <stopErp>0.0</stopErp> -->
</gazebo> </gazebo>
</xacro:macro> </xacro:macro>
</root> </root>
......
...@@ -30,12 +30,13 @@ ...@@ -30,12 +30,13 @@
</collision> </collision>
</link> </link>
<joint name="${parent}_2_${name}_wheel_joint" type="continuous"> <joint name="${parent}_2_${name}_wheel_joint" type="revolute">
<xacro:insert_block name="origin" /> <xacro:insert_block name="origin" />
<parent link="${parent}"/> <parent link="${parent}"/>
<child link="${name}_wheel"/> <child link="${name}_wheel"/>
<axis xyz="0 0 ${direction}"/> <axis xyz="0 0 ${direction}"/>
<limit effort="5" velocity="1.0"/> <limit effort="0.1" velocity="20.0" upper="1e16" lower="-1e16"/>
<!-- the limits only apply to revolute and prismatic joints -->
</joint> </joint>
<transmission name="${name}_tran"> <transmission name="${name}_tran">
......
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