Skip to content

Commit

Permalink
feat: update steering input delay for JT5 (#547)
Browse files Browse the repository at this point in the history
* feat: update steering input delay for JT5

* style(pre-commit): autofix

---------

Co-authored-by: shiorikawata <[email protected]>
  • Loading branch information
shiorikawata and shiorikawata authored Jul 7, 2023
1 parent 1a3cd22 commit 05deed1
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@

# -- vehicle model --
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
input_delay: 0.1 # steering input delay time for delay compensation
input_delay: 0.3 # steering input delay time for delay compensation
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
steer_rate_lim_dps: 20.0 # steering angle rate limit [deg/s]
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]
Expand Down
14 changes: 7 additions & 7 deletions autoware_launch/launch/e2e_simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,13 @@

<!-- dummy topic publisher (camera0 ~ camera6)-->
<!-- temporary until AWSIM supports object recoginition camera -->
<arg name="camera0_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera0/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera1_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera1/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera2_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera2/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera3_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera3/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera4_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera4/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera5_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera5/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera6_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera6/camera_info sensor_msgs/msg/CameraInfo '{}'" />
<arg name="camera0_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera0/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera1_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera1/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera2_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera2/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera3_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera3/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera4_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera4/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera5_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera5/camera_info sensor_msgs/msg/CameraInfo '{}'"/>
<arg name="camera6_pub" default="ros2 topic pub --rate 10 /sensing/camera/camera6/camera_info sensor_msgs/msg/CameraInfo '{}'"/>

<executable cmd="$(var camera0_pub)" name="camera0" shell="true"/>
<executable cmd="$(var camera1_pub)" name="camera1" shell="true"/>
Expand Down

0 comments on commit 05deed1

Please sign in to comment.