Skip to content
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
2 changes: 1 addition & 1 deletion config/mainConfig.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
pacsim:
timeouts:
start: 60 # time to trigger first timekeeping gate
start: 300 # time to trigger first timekeeping gate
acceleration: 25
autocross: 300
skidpad: 90
Expand Down
8 changes: 4 additions & 4 deletions src/VehicleModel/VehicleModelBicycle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,13 +92,13 @@ class VehicleModelBicycle : public IVehicleModel
double avgRatio = 0.5 * (this->innerSteeringRatio + this->outerSteeringRatio);
if (in > 0)
{
this->steeringAngles.FL = this->innerSteeringRatio * in;
this->steeringAngles.FR = this->outerSteeringRatio * in;
this->steeringAngles.FL = this->innerSteeringRatio * in / avgRatio;
this->steeringAngles.FR = this->outerSteeringRatio * in / avgRatio;
}
else
{
this->steeringAngles.FL = this->outerSteeringRatio * in;
this->steeringAngles.FR = this->innerSteeringRatio * in;
this->steeringAngles.FL = this->outerSteeringRatio * in / avgRatio;
this->steeringAngles.FR = this->innerSteeringRatio * in / avgRatio;
}
return;
}
Expand Down
18 changes: 9 additions & 9 deletions urdf/separate_model.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
</link>
<link name="Modell">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<origin xyz="0 0 0" rpy="-1.57 0 0" />
<geometry>
<mesh filename="package://pacsim/urdf/Model_without_Steering_Tires.stl" scale="0.01 0.01 0.01"/>
</geometry>
Expand All @@ -19,7 +19,7 @@
</link>
<link name="FL_inside">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FL_Inside.stl" scale="0.01 0.01 0.01"/>
</geometry>
Expand All @@ -28,55 +28,55 @@
</link>
<link name="FL_outside">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FL_Outside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="FR_inside">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FR_Inside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="FR_outside">
<visual>
<origin rpy="0.0 0 3.1415" xyz="0 0 0"/>
<origin rpy="-1.57 0 3.1415" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FL_Outside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="RR_inside">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/RR_Inside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="RR_outside">
<visual>
<origin rpy="0.0 0 3.14" xyz="0 0 0"/>
<origin rpy="-1.57 0 3.14" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FL_Outside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="RL_inside">
<visual>
<origin rpy="0.0 0 3.1415" xyz="0 0 0"/>
<origin rpy="-1.57 0 3.1415" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/RR_Inside.stl" scale="0.01 0.01 0.01"/>
</geometry>
</visual>
</link>
<link name="RL_outside">
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<origin rpy="-1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://pacsim/urdf/FL_Outside.stl" scale="0.01 0.01 0.01"/>
</geometry>
Expand Down