Skip to content

Commit

Permalink
feat(data_collecting_tool): improve data collection logic (#108)
Browse files Browse the repository at this point in the history
* create data collection logic

Signed-off-by: Yoshihiro Kogure <[email protected]>

* remove an unnecessary comment

Signed-off-by: Yoshihiro Kogure <[email protected]>

* remove uncessary codes and fix some params

Signed-off-by: Yoshihiro Kogure <[email protected]>

* style(pre-commit): autofix

* add u_shaped course and straight line

Signed-off-by: Yoshihiro Kogure <[email protected]>

* add backwards straight line

Signed-off-by: Yoshihiro Kogure <[email protected]>

* define parameters as global variables

Signed-off-by: Yoshihiro Kogure <[email protected]>

* style(pre-commit): autofix

* revert_merge

Signed-off-by: Yoshihiro Kogure <[email protected]>

* style(pre-commit): autofix

* apply pre-commit run

Signed-off-by: Yoshihiro Kogure <[email protected]>

* modify README

Signed-off-by: Yoshihiro Kogure <[email protected]>

* style(pre-commit): autofix

* modify spell

Signed-off-by: Yoshihiro Kogure <[email protected]>

---------

Signed-off-by: Yoshihiro Kogure <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
YoshihiroKogure and pre-commit-ci[bot] authored Sep 9, 2024
1 parent 5bd5865 commit 75537a7
Show file tree
Hide file tree
Showing 3 changed files with 379 additions and 82 deletions.
12 changes: 6 additions & 6 deletions control_data_collecting_tool/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -87,11 +87,11 @@ ROS 2 params in `/data_collecting_trajectory_publisher` node:
| :--------------------------------------- | :------- | :-------------------------------------------------------------------- | :------------ |
| `max_lateral_accel` | `double` | Max lateral acceleration limit [m/ss] | 0.5 |
| `lateral_error_threshold` | `double` | Lateral error threshold where applying velocity limit [m/s] | 5.0 |
| `yaw_error_threshold` | `double` | Yaw error threshold where applying velocity limit [rad] | 0.5 |
| `velocity_limit_by_tracking_error` | `double` | Velocity limit applied when tracking error exceeds threshold [m/s] | 2.0 |
| `yaw_error_threshold` | `double` | Yaw error threshold where applying velocity limit [rad] | 0.75 |
| `velocity_limit_by_tracking_error` | `double` | Velocity limit applied when tracking error exceeds threshold [m/s] | 1.0 |
| `mov_ave_window` | `int` | Moving average smoothing window size | 50 |
| `target_longitudinal_velocity` | `double` | Target longitudinal velocity [m/s] | 6.0 |
| `longitudinal_velocity_noise_amp` | `double` | Target longitudinal velocity additional sine noise amplitude [m/s] | 0.1 |
| `longitudinal_velocity_noise_amp` | `double` | Target longitudinal velocity additional sine noise amplitude [m/s] | 0.01 |
| `longitudinal_velocity_noise_min_period` | `double` | Target longitudinal velocity additional sine noise minimum period [s] | 5.0 |
| `longitudinal_velocity_noise_max_period` | `double` | Target longitudinal velocity additional sine noise maximum period [s] | 20.0 |

Expand All @@ -101,9 +101,9 @@ ROS 2 params in `/data_collecting_pure_pursuit_trajectory_follower` node:
| :--------------------------------------- | :------- | :------------------------------------------------------------- | :------------ |
| `pure_pursuit_type` | `string` | Pure pursuit type (`naive` or `linearized` steer control law ) | `linearized` |
| `wheel_base` | `double` | Wheel base [m] | 2.79 |
| `acc_kp` | `double` | Accel command proportional gain | 0.5 |
| `lookahead_time` | `double` | Pure pursuit lookahead time [s] | 1.5 |
| `min_lookahead` | `double` | Pure pursuit minimum lookahead length [m] | 3.0 |
| `acc_kp` | `double` | Accel command proportional gain | 1.0 |
| `lookahead_time` | `double` | Pure pursuit lookahead time [s] | 2.0 |
| `min_lookahead` | `double` | Pure pursuit minimum lookahead length [m] | 2.0 |
| `linearized_pure_pursuit_steer_kp_param` | `double` | Linearized pure pursuit steering P gain parameter | 2.0 |
| `linearized_pure_pursuit_steer_kd_param` | `double` | Linearized pure pursuit steering D gain parameter | 2.0 |
| `stop_acc` | `double` | Accel command for stopping data collecting driving [m/ss] | -2.0 |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,19 +60,19 @@ def __init__(self):

self.declare_parameter(
"acc_kp",
0.5,
1.0,
ParameterDescriptor(description="Pure pursuit accel command proportional gain"),
)

self.declare_parameter(
"lookahead_time",
1.5,
2.0,
ParameterDescriptor(description="Pure pursuit lookahead length coef [m/(m/s)]"),
)

self.declare_parameter(
"min_lookahead",
3.0,
2.0,
ParameterDescriptor(description="Pure pursuit lookahead length intercept [m]"),
)

Expand All @@ -98,7 +98,7 @@ def __init__(self):

self.declare_parameter(
"stop_jerk_lim",
1.0,
2.0,
ParameterDescriptor(
description="Jerk limit for stopping data collecting driving [m/sss]"
),
Expand All @@ -107,7 +107,7 @@ def __init__(self):
# lim default values are taken from https://github.com/autowarefoundation/autoware.universe/blob/e90d3569bacaf64711072a94511ccdb619a59464/control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml
self.declare_parameter(
"lon_acc_lim",
5.0,
2.0,
ParameterDescriptor(description="Longitudinal acceleration limit [m/ss]"),
)

Expand All @@ -131,14 +131,14 @@ def __init__(self):

self.declare_parameter(
"acc_noise_amp",
0.05,
0.00,
ParameterDescriptor(description="Accel cmd additional sine noise amplitude [m/ss]"),
)

self.declare_parameter(
"acc_noise_min_period",
5.0,
ParameterDescriptor(description="Accel cmd additional sine noise minimum period [s]"),
ParameterDescriptor(description="Accel cmd additional sineW noise minimum period [s]"),
)

self.declare_parameter(
Expand All @@ -149,7 +149,7 @@ def __init__(self):

self.declare_parameter(
"steer_noise_amp",
0.01,
0.00,
ParameterDescriptor(description="Steer cmd additional sine noise amplitude [rad]"),
)

Expand Down
Loading

0 comments on commit 75537a7

Please sign in to comment.