Skip to content

Commit 05deed1

Browse files
authored
feat: update steering input delay for JT5 (#547)
* feat: update steering input delay for JT5 * style(pre-commit): autofix --------- Co-authored-by: shiorikawata <[email protected]>
1 parent 1a3cd22 commit 05deed1

File tree

2 files changed

+8
-8
lines changed

2 files changed

+8
-8
lines changed

autoware_launch/config/control/trajectory_follower/5/lateral/mpc.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@
4545

4646
# -- vehicle model --
4747
vehicle_model_type: "kinematics" # vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
48-
input_delay: 0.1 # steering input delay time for delay compensation
48+
input_delay: 0.3 # steering input delay time for delay compensation
4949
vehicle_model_steer_tau: 0.1 # steering dynamics time constant (1d approximation) [s]
5050
steer_rate_lim_dps: 20.0 # steering angle rate limit [deg/s]
5151
acceleration_limit: 1.0 # acceleration limit for trajectory velocity modification [m/ss]

autoware_launch/launch/e2e_simulator.launch.xml

+7-7
Original file line numberDiff line numberDiff line change
@@ -40,13 +40,13 @@
4040

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

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

0 commit comments

Comments
 (0)