Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Help Request] Need to customize vehicle parameters #2116

Closed
Frzgunr1 opened this issue Nov 27, 2023 · 9 comments · Fixed by #2117 or #2130
Closed

[Help Request] Need to customize vehicle parameters #2116

Frzgunr1 opened this issue Nov 27, 2023 · 9 comments · Fixed by #2117 or #2130
Assignees
Labels
help wanted Extra attention is needed

Comments

@Frzgunr1
Copy link

High Level Description

I need to customize the parameters of the vehicle for my research using SMARTS, for example, I want to create a truck with a different crashbox than a normal vehicle and I want it to have a different color in the visualization.
 Which files do I need to modify in this case?
  Looking forward to your help, I will cite SMARTS in my paper. thank you very much!

Version

ver [1.4.0]

Operating System

ubuntu 20.04

Problems

No response

@Frzgunr1 Frzgunr1 added the help wanted Extra attention is needed label Nov 27, 2023
@Frzgunr1
Copy link
Author

  I noticed a previous issue mentioning the feature, but based on the description, it appears to be hidden. I'd like to know how to customize their crashboxes and specify colors (max acceleration and chassis if possible) after adding agents.
  If possible, could you please tell me in which files there are such cases, or a general approach on how to implement the feature.   
   THX!

@Gamenot
Copy link
Collaborator

Gamenot commented Nov 28, 2023

Hello @Frzgunr1, I will look into this tomorrow to see what work would be involved.

Do you have a specific model of truck you are looking for? The main resource requirement is a urdf file of the vehicle you want.

@Frzgunr1
Copy link
Author

   Hi @Gamenot , I have not implemented a separate urdf modeling for truck at the moment, if possible you could use the truck mentioned in #767  instead. 
   Agent is always of type car when generated, however I noticed that the `SMARTS/smarts/ core/vehicle_state.py` file has some different vehicles than when the smarts are generated, hopefully it will be possible to implement the ability to specify the vehicle parameter of the agent (at least the collision box) when customizing the agent!
  Looking forward to hearing back from you!  :)

@Gamenot
Copy link
Collaborator

Gamenot commented Nov 28, 2023

Hello @Frzgunr1, what is given in #767 is unfortunately just a set of visual models, it is still missing the dynamics model.

The two current physics models are hardcoded in vehicle.py to draw from smarts/core/models/ one of vehicle.urdf ("sedan") or bus.urdf ("bus") based on the value of AgentInterface.vehicle_type.

Question

What is your timeline?

@Gamenot
Copy link
Collaborator

Gamenot commented Nov 28, 2023

Investigation

There are a few components to a vehicle within our simulation.

  • Visuals
  • Physics model
  • Controller model
  • Selection

Selection (via AgentInterface)

Current vehicle selection is done in the agent interface:

vehicle_type: str = "sedan"
"""
The choice of vehicle type.
"""

And constrained:

assert self.vehicle_type in {"sedan", "bus"}

This currently is resolved to a urdf when the vehicle is constructed:

if agent_interface.vehicle_type == "sedan":
urdf_name = "vehicle"
elif agent_interface.vehicle_type == "bus":
urdf_name = "bus"
else:
raise Exception("Vehicle type does not exist!!!")

Visuals

The vehicle state is where the visual representation of the vehicle is resolved and where the simulation is intended to redirect to the appropriate .glb.

VEHICLE_CONFIGS = {
"passenger": VehicleConfig(
vehicle_type="car",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=3.68, width=1.47, height=1.4),
glb_model="simple_car.glb",
),
"bus": VehicleConfig(
vehicle_type="bus",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=7, width=2.25, height=3),
glb_model="bus.glb",
),
"coach": VehicleConfig(
vehicle_type="coach",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=8, width=2.4, height=3.5),
glb_model="coach.glb",
),
"truck": VehicleConfig(
vehicle_type="truck",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=5, width=1.91, height=1.89),
glb_model="truck.glb",
),
"trailer": VehicleConfig(
vehicle_type="trailer",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=10, width=2.5, height=4),
glb_model="trailer.glb",
),
"pedestrian": VehicleConfig(
vehicle_type="pedestrian",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=0.5, width=0.5, height=1.6),
glb_model="pedestrian.glb",
),
"motorcycle": VehicleConfig(
vehicle_type="motorcycle",
color=SceneColors.SocialVehicle,
dimensions=Dimensions(length=2.5, width=1, height=1.4),
glb_model="motorcycle.glb",
),
}

It also looks like there is currently a bug that does not forward the visual vehicle configuration and default dimensions when generating agents:

vehicle = Vehicle(
id=vehicle_id,
chassis=chassis,
color=vehicle_color,
)

This would normally be done through specifying vehicle_config_type (relating to VEHICLE_CONFIGS).

class Vehicle:
"""Represents a single vehicle."""
_HAS_DYNAMIC_ATTRIBUTES = True # dynamic pytype attribute
def __init__(
self,
id: str,
chassis: Chassis,
vehicle_config_type: str = "passenger",
color: Optional[SceneColors] = None,
action_space=None,
):

Physics

The physics is represented in the following way:

Bus

<?xml version="1.0"?>
<!-- note: if inertia values are set to 0, bullet will re-compute our inertias for us-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="vehicle">
<link name="base_link">
<inertial>
<mass value="1"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<link name="chassis">
<collision name="chassis">
<origin xyz="0.0 0.0 1.4" rpy="0 0 0"/>
<geometry>
<box size="2.2026 7 2.4"/>
</geometry>
</collision>
<inertial>
<mass value="6000.0"/>
<origin xyz="0 -0.1 0.20" rpy="0 0 1.5708"/>
<inertia ixx="27380" ixy="0.0" ixz="0.0" iyy="5300" iyz="0.0" izz="26920"/>
</inertial>
</link>
<link name="fl_axle">
<inertial>
<mass value="5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="6" izz="0"/>
</inertial>
</link>
<link name="fr_axle">
<inertial>
<mass value="5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="6" izz="0"/>
</inertial>
</link>
<link name="front_left_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="front_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="front_right_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="front_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="rear_left_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="rear_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<link name="rear_right_wheel">
<inertial>
<mass value="25"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="4"/>
</inertial>
<collision name="rear_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.35" radius="0.52"/>
</geometry>
</collision>
</link>
<joint name="base_link_connection" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="0 0 0" rpy="0 0 3.141592653589793"/>
</joint>
<joint name="front_left_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fl_axle"/>
<origin xyz="0.5 -2.5 0.5" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_right_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fr_axle"/>
<origin xyz="-0.5 -2.5 0.5" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="fl_axle"/>
<child link="front_left_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="fr_axle"/>
<child link="front_right_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_left_wheel"/>
<origin xyz="0.5 2.5 0.5" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.5 2.5 0.5" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
</robot>

Sedan

<?xml version="1.0"?>
<!-- note: if inertia values are set to 0, bullet will re-compute our inertias for us-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="vehicle">
<link name="base_link">
<inertial>
<mass value="1"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
</link>
<link name="chassis">
<collision name="chassis">
<origin xyz="0.0 0.0 0.6" rpy="0 0 0"/>
<geometry>
<box size="1.47 3.68 1"/>
</geometry>
</collision>
<inertial>
<mass value="2356.0"/>
<origin xyz="0 -0.1 0.20" rpy="0 0 1.5708"/>
<inertia ixx="2581.13354740" ixy="0.0" ixz="0.0" iyy="591.30846112" iyz="0.0" izz="2681.95008628"/>
</inertial>
</link>
<link name="fl_axle">
<inertial>
<mass value="1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="3" izz="0"/>
</inertial>
</link>
<link name="fr_axle">
<inertial>
<mass value="1"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="3" izz="0"/>
</inertial>
</link>
<link name="front_left_wheel">
<inertial>
<mass value="15"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="2"/>
</inertial>
<collision name="front_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.25" radius="0.31265"/>
</geometry>
</collision>
</link>
<link name="front_right_wheel">
<inertial>
<mass value="15"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="2"/>
</inertial>
<collision name="front_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.25" radius="0.31265"/>
</geometry>
</collision>
</link>
<link name="rear_left_wheel">
<inertial>
<mass value="15"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="2"/>
</inertial>
<collision name="rear_left_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.25" radius="0.31265"/>
</geometry>
</collision>
</link>
<link name="rear_right_wheel">
<inertial>
<mass value="15"/>
<origin xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="2"/>
</inertial>
<collision name="rear_right_wheel_collision">
<origin rpy="0 1.5707963267948966 0"/>
<geometry>
<cylinder length="0.25" radius="0.31265"/>
</geometry>
</collision>
</link>
<joint name="base_link_connection" type="fixed">
<parent link="base_link"/>
<child link="chassis"/>
<origin xyz="0 0 0" rpy="0 0 3.141592653589793"/>
</joint>
<joint name="front_left_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fl_axle"/>
<origin xyz="0.5 -1.5 0.3" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_right_steer_joint" type="revolute">
<parent link="chassis"/>
<child link="fr_axle"/>
<origin xyz="-0.5 -1.5 0.3" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-0.8727" upper="0.8727" effort="10000000" velocity="1000000"/>
</joint>
<joint name="front_left_wheel_joint" type="continuous">
<parent link="fl_axle"/>
<child link="front_left_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="front_right_wheel_joint" type="continuous">
<parent link="fr_axle"/>
<child link="front_right_wheel"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_left_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_left_wheel"/>
<origin xyz="0.5 1.5 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="rear_right_wheel_joint" type="continuous">
<parent link="chassis"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.5 1.5 0.3" rpy="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
</robot>

There appears to be a second bug related to vehicle selection in which the vehicle can only ever have the dimensions of the default "passenger" vehicle instead of using information from the AgentInterface.vehicle_type.

chassis_dims = cls.agent_vehicle_dims(mission)

@staticmethod
def agent_vehicle_dims(mission: Mission) -> Dimensions:
"""Get the vehicle dimensions from the mission requirements.
Args:
A mission for the agent.
Returns:
The mission vehicle spec dimensions XOR the default "passenger" vehicle dimensions.
"""
if mission.vehicle_spec:
# mission.vehicle_spec.veh_config_type will always be "passenger" for now,
# but we use that value here in case we ever expand our history functionality.
vehicle_config_type = mission.vehicle_spec.veh_config_type
return Dimensions.copy_with_defaults(
mission.vehicle_spec.dimensions,
VEHICLE_CONFIGS[vehicle_config_type].dimensions,
)
# non-history agents can currently only control passenger vehicles.
vehicle_config_type = "passenger"
return VEHICLE_CONFIGS[vehicle_config_type].dimensions

Controller

The controller arguments are currently defined here:

sedan:
control:
final_heading_gain: .15
final_lateral_gain: 4.65
final_steering_filter_constant: 23.5
throttle_filter_constant: 22.5
velocity_gain: 5.1
velocity_integral_gain: 0
traction_gain: 6
final_lateral_error_derivative_gain: 0.3
final_heading_error_derivative_gain: 3.1
initial_look_ahead_distant: 6
derivative_activation: 1
speed_reduction_activation: 1
velocity_damping_gain: 0.001
windup_gain: 0.01
chassis:
chassis_aero_force_gain : 0.63
max_brake_gain : 10000
max_turn_radius : 2.2
wheel_radius : 0.31265
max_torque : 1600
max_btorque : 1400
max_steering : 12.56
steering_gear_ratio : 17.4
bus:
control:
final_heading_gain: 0.15
final_lateral_gain: 5.3
final_steering_filter_constant: 27.5
throttle_filter_constant: 2
velocity_gain: 6.1
velocity_integral_gain: 0
traction_gain: 8
final_lateral_error_derivative_gain: 0.45
final_heading_error_derivative_gain: 2.5
initial_look_ahead_distant: 3
derivative_activation: 1
speed_reduction_activation: 0
velocity_damping_gain: 0.001
windup_gain: 0.01
chassis:
chassis_aero_force_gain : 0.63
max_brake_gain : 10000
max_turn_radius : 2.2
wheel_radius : 0.31265
max_torque : 2100
max_btorque : 1200
max_steering : 12.56
steering_gear_ratio : 17.4

It looks like there is a final bug where if a vehicle is replaced (rather than a new vehicle generated) no configuration is used and defaults to "sedan":

chassis = AckermannChassis(pose=vehicle.pose, bullet_client=sim.bc)

class AckermannChassis(Chassis):
"""Control a vehicle by applying forces on its joints. The joints and links are
defined by a URDF file.
"""
def __init__(
self,
pose: Pose,
bullet_client: bc.BulletClient,
vehicle_filepath=DEFAULT_VEHICLE_FILEPATH,
tire_parameters_filepath=None,
friction_map=None,
controller_parameters=DEFAULT_CONTROLLER_PARAMETERS,
initial_speed=None,
):

with pkg_resources.path(models, "vehicle.urdf") as path:
DEFAULT_VEHICLE_FILEPATH = str(path.absolute())
with pkg_resources.path(models, "controller_parameters.yaml") as controller_path:
controller_filepath = str(controller_path.absolute())
with open(controller_filepath, "r") as controller_file:
DEFAULT_CONTROLLER_PARAMETERS = yaml.safe_load(controller_file)["sedan"]

Configuration is intended to be provided such as with a newly generated vehicle:

chassis = AckermannChassis(
pose=start_pose,
bullet_client=sim.bc,
vehicle_filepath=vehicle_filepath,
tire_parameters_filepath=tire_filepath,
friction_map=surface_patches,
controller_parameters=controller_parameters,
initial_speed=initial_speed,
)

@Gamenot
Copy link
Collaborator

Gamenot commented Nov 28, 2023

Result

  • I will do a fix of the 3 bugs that I noted above tomorrow.
  • I will patch in the remaining vehicle configuration options (particularly the truck configuration) but you will need to modify some things as you need.
    • You would need to acquire a truck urdf
    • You would need to tune the controller
  • I will expand the colour configuration in the scenario to also affect agents.
  • I am unable to get to a broader vehicle configuration interface until the middle of next month.
  • I am unable to do controller tuning until later next month.

@Gamenot Gamenot linked a pull request Nov 28, 2023 that will close this issue
@Gamenot Gamenot self-assigned this Nov 28, 2023
@Frzgunr1
Copy link
Author

Hi @Gamenot , you're right, thank you very much for your analyses, they are very accurate and readable, you're a great engineer.
Considering the current situation, I am going to write the text part of the paper first. I will wait for you to finish this important work and, if there is any material I can provide, just tell me.
THX :)

@Gamenot
Copy link
Collaborator

Gamenot commented Dec 15, 2023

@Frzgunr1 I am about to start work on this, is there a particular grade of truck you are looking for?

  • Large pickup truck (e.g. Ford F150, Toyota Tacoma)
  • Small semi-trailer (e.g. Toyota Dyna)
  • Large semi-trailer (e.g. Mack, Kenworth, Mercedes FAW)
  • Integrated (e.g. garbage truck, fire engine, ambulance)

Alternatively, the truck (7.1m 2.4m 2.4m) as is defined by SUMO.

@Frzgunr1
Copy link
Author

Sure,just use the truck (7.1m) as is defined by SUMO.
Then We could make more customized vehicles!

@Gamenot Gamenot linked a pull request Jan 2, 2024 that will close this issue
15 tasks
@Gamenot Gamenot mentioned this issue Jan 2, 2024
15 tasks
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
help wanted Extra attention is needed
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants