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

Feature/add vehicle config #323

Merged
merged 5 commits into from
Feb 27, 2024
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
145 changes: 145 additions & 0 deletions ail_vru_uc1_scenario/cdasim_config/carma/VehicleConfigParams.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,145 @@
# Defines the ros parameters which define the characteristics of this host vehicle configuration
# The value type field is used to indicate how the field should be set.
# Should it be treated as a measured value (Measured) or a desired behavior constraint (Desired)
use_sim_time: true

# String: Host vehicle make
# Value type: Measured
vehicle_make: 'greased'

# String: Host vehicle model
# Value type: Measured
vehicle_model: 'lightning'

# Integer: Host vehicle year
# Value type: Measured
# Units: Year
vehicle_year: 2019

# Double: Host vehicle length
# Value type: Measured
# Units: Meters
vehicle_length: 5.0

# Double: Host vehicle width
# Value type: Measured
# Units: Meters
vehicle_width: 3.0

# Double: Host vehicle height
# Value type: Measured
# Units: Meters
vehicle_height: 2.0

# Double: Distance from front axel to rear axel
# Value type: Measured
# Units: Meters
vehicle_wheel_base: 2.79

# Double: Radius of the tires
# Value type: Measured
# Units: Meters
vehicle_tire_radius: 0.39

# Int: The maximum duration that Plan Delegator will wait after calling a tactical plugin's trajectory planning service; if trajectory
# generation takes longer than this, then trajectory planning will immediately end for the current trajectory planning iteration.
# NOTE: It is highly desirable to maintain a timeout of 100 ms or less, but trajectory generation success cannot be guaranteed with this duration
# for tactical plugins (primarily cooperative_lanechange) in all test scenarios at this time.
# Units: Milliseconds
tactical_plugin_service_call_timeout: 300

# Activates object avoidance logics in trajectory planning plugins
# Units: Boolean
enable_object_avoidance: true

# Acceleration limit
# Value type: Desired
# Units: m/s^2
vehicle_acceleration_limit: 2.0

# Deceleration limit
# Value type: Desired
# Units: m/s^2
vehicle_deceleration_limit: 2.0

# Lateral Acceleration Limit
# Value type: Desired
# Units: m/s^2
vehicle_lateral_accel_limit: 2.3

# Lateral Jerk Limit
# Value type: Desired
# Units: m/s^3
vehicle_lateral_jerk_limit: 2.0

# Max curvature rate
# Value type: Desired
# Units: (m^-1) / s
vehicle_max_curvature_rate: 0.75

# Ratio relating the steering wheel angle and the tire position on the road
# Value type: Measured
# (radians of a full steering wheel rotation) / (radians of tires with the longitudinal axis under full steer)
vehicle_steering_gear_ratio: 16.863

# Maximum steering angle of the wheel relative to the vehicle centerline.
# Value type: Measured
# Unit: deg
vehicle_steer_lim_deg: 29.2

# steering dynamics time constant
# Value type: Measured
# Unit: s
vehicle_model_steer_tau : 0.3

# Parameter to enable configurable speed limit
# Value type: Desired
config_speed_limit: 20.0

# Vehicle Participation Type corresponding to the Lanelet2 participant type standards.
# Used for interpreting traffic rules in world model instances
vehicle_participant_type: "vehicle:car"

# Parameters to enable either ROS 1 or ROS 2 (or both) rosbag logging
use_ros1_rosbag: true
use_ros2_rosbag: false

# Topics to exclude from rosbag recording
exclude_default: true
excluded_default_topics:
- (.*)/received_messages
- (.*)/sent_messages
- (.*)/scan

exclude_lidar: true
excluded_lidar_topics:
- /detection/lidar_detector/objects
- /detection/lidar_detector/objects_markers
- /hardware_interface/lidar/points_raw
- /hardware_interface/camera/projection_matrix/detection/lidar_detector/cloud_clusters
- /environment/range_vision_fusion_01/detection/lidar_detector/objects
- /environment/detection/fusion_tools/objects
- /environment/detection/fusion_tools/objects_markers
- /environment/detection/object_tracker/objects
- /environment/detection/object_tracker/objects_markers
- /environment/detection/objects

exclude_camera: true
excluded_camera_topics:
- /hardware_interface/camera/camera_info
- /hardware_interface/camera/image_raw
- /hardware_interface/camera/image_rect
- /hardware_interface/camera/image_rects
- /hardware_interface/camera/projection_matrix/detection/lidar_detector/cloud_clusters
- /environment/range_vision_fusion_01/detection/image_detector/objects
- /environment/vision_beyond_track_01/detection/image_detector/objects
- /environment/detection/fusion_tools/objects
- /environment/detection/fusion_tools/objects_markers
- /environment/detection/object_tracker/objects
- /environment/detection/object_tracker/objects_markers
- /environment/detection/objects

exclude_can: false
excluded_can_topics:
- /hardware_interface/ds_fusion/can_bus_dbw/can_rx
- /hardware_interface/ds_fusion/can_bus_dbw/can_tx
2 changes: 2 additions & 0 deletions ail_vru_uc1_scenario/docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ services:
- /opt/carma/routes:/opt/carma/routes
- /opt/carma/data:/opt/carma/data
- /opt/carma/simulation:/opt/carma/simulation
- ./carma/VehicleConfigParams.yaml:/opt/carma/vehicle/config/VehicleConfigParams.yaml
environment:
- ROS_IP=172.3.0.3
- ROS_MASTER_URI=http://172.3.0.2:11311/
Expand All @@ -82,6 +83,7 @@ services:
- ./inlanecruising_config/parameters.yaml:/opt/carma/install_ros2/inlanecruising_plugin/share/inlanecruising_plugin/config/parameters.yaml
- ./carma/launch/environment.launch.py:/opt/carma/install_ros2/carma/share/carma/launch/environment.launch.py
- ./yield_plugin/parameters.yaml:/opt/carma/install_ros2/yield_plugin/share/yield_plugin/config/parameters.yaml
- ./carma/VehicleConfigParams.yaml:/opt/carma/vehicle/config/VehicleConfigParams.yaml
command: >
bash -c 'export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
&& source /opt/carma/install_ros2/setup.bash
Expand Down