Skip to content

Commit

Permalink
feat(control_data_collecting_tool): add trajectory inside circle and …
Browse files Browse the repository at this point in the history
…lanelet2 trajectory (#156)

* Add trajectory inside circle

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

* Fix bug

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

* Add lanelet2 trajectory

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

* pre-commit run

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

* Fix bug

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

* pre-commit

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

* Update README.md

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

* Add parameter descriptions to the README

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

* style(pre-commit): autofix

* Revise the content

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

* style(pre-commit): autofix

* Update README

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

* Update README

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

* Add comments

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

* Update prameters for along_road course

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

* style(pre-commit): autofix

* Add default mask and mask selector

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

* Add mask to plotter

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

* Data collection concerning Mask

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

* Modify the code to publish the pose

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

* style(pre-commit): autofix

* Modify to work even when map_path is not provided

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

* Add steer rate plot

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

* Update README.md and fix typo

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

* Changes to the README and parameter values

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

* fix markdownlint

Signed-off-by: kosuke55 <[email protected]>

* ignore prettier

Signed-off-by: kosuke55 <[email protected]>

* Fix typo

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

* style(pre-commit): autofix

* Add cpell:ignore

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

* Remove cspell:ignore

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

* style(pre-commit): autofix

* Revert "style(pre-commit): autofix"

This reverts commit 1cdbd05.

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

* Revert "Merge branch 'feat/default_mask' into feat/trajectory_inside_circle_and_lanelet2_trajectory"

This reverts commit d372051, reversing
changes made to 50f46bd.

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

---------

Signed-off-by: Yoshihiro Kogure <[email protected]>
Signed-off-by: kosuke55 <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: kosuke55 <[email protected]>
  • Loading branch information
3 people authored Dec 2, 2024
1 parent a7c02c8 commit f3e9313
Show file tree
Hide file tree
Showing 40 changed files with 3,958 additions and 953 deletions.
46 changes: 30 additions & 16 deletions control_data_collecting_tool/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,39 +4,53 @@ project(control_data_collecting_tool)
find_package(autoware_cmake REQUIRED)
autoware_package()

# Configure Qt5
find_package(Qt5 REQUIRED COMPONENTS Core Widgets)
set(QT_LIBRARIES Qt5::Widgets)
set(CMAKE_AUTOMOC ON)

# Find necessary ROS 2 packages
find_package(rviz_common REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)

# Build the library as a plugin
ament_auto_add_library(${PROJECT_NAME} SHARED
src/data_collecting_area_selection.cpp
src/data_collecting_goal_pose.cpp
)

# Link necessary libraries
ament_target_dependencies(${PROJECT_NAME}
Qt5
rviz_common
pluginlib
rclcpp
)

# Export the plugin XML file
pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml)

# Install scripts
install(PROGRAMS
scripts/data_collecting_pure_pursuit_trajectory_follower.py
scripts/data_collecting_trajectory_publisher.py
scripts/data_collecting_plotter.py
scripts/data_collecting_rosbag_record.py
scripts/data_collecting_data_counter.py
scripts/data_collecting_base_node.py
scripts/rosbag_play.py
DESTINATION lib/${PROJECT_NAME}
)

# Install other configurations and files
install(
DIRECTORY config/
DESTINATION share/${PROJECT_NAME}/config
)

find_package(Qt5 REQUIRED Core Widgets)
set(QT_LIBRARIES Qt5::Widgets)

set(CMAKE_AUTOMOC ON)


ament_auto_add_library(${PROJECT_NAME} SHARED
src/data_collecting_area_selection.cpp
)

target_link_libraries(${PROJECT_NAME}
${QT_LIBRARIES})

pluginlib_export_plugin_description_file(rviz_common plugins/plugin_description.xml)

install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})

# Build configuration for the package
ament_auto_package(
INSTALL_TO_SHARE
plugins
Expand Down
282 changes: 187 additions & 95 deletions control_data_collecting_tool/README.md

Large diffs are not rendered by default.

42 changes: 42 additions & 0 deletions control_data_collecting_tool/config/common_param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
/**:
ros__parameters:
LOAD_ROSBAG2_FILES: true

# COURSE_NAME: eight_course
# COURSE_NAME: u_shaped_return
# COURSE_NAME: straight_line_positive
# COURSE_NAME: straight_line_negative
COURSE_NAME: reversal_loop_circle
# COURSE_NAME: along_road

NUM_BINS_V: 10
NUM_BINS_STEER: 20
NUM_BINS_A: 10
V_MIN: 0.0
V_MAX: 11.5
STEER_MIN: -0.6
STEER_MAX: 0.6
A_MIN: -1.0
A_MAX: 1.0

max_lateral_accel: 2.00
lateral_error_threshold: 1.50
yaw_error_threshold: 0.75
velocity_limit_by_tracking_error: 1.0
mov_ave_window: 50
target_longitudinal_velocity: 6.0

pure_pursuit_type: linearized
# pure_pursuit_type: naive
wheel_base: 2.79
acc_kp: 1.0
lookahead_time: 2.0
min_lookahead: 2.0
linearized_pure_pursuit_steer_kp_param: 2.0
linearized_pure_pursuit_steer_kd_param: 2.0
stop_acc: -2.0
stop_jerk_lim: 5.0
lon_acc_lim: 1.5
lon_jerk_lim: 0.5
steer_lim: 0.6
steer_rate_lim: 0.6
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
/**:
ros__parameters:
# Course Specific Parameters
velocity_on_curve: 3.5
stopping_distance: 15.0
course_width: 1.5
smoothing_window: 100
length_of_straight_line: 50.0
longitude: 139.6503
latitude: 35.6762

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
/**:
ros__parameters:
# Course Specific Parameters
velocity_on_curve: 4.5
smoothing_window: 400

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
# Course Specific Parameters
trajectory_radius: 35.0
enclosing_radius: 40.0
look_ahead_distance: 15.0

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
# Course Specific Parameters
stopping_buffer_distance: 10.0

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
# Course Specific Parameters
stopping_buffer_distance: 10.0

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
# Course Specific Parameters
velocity_on_curve: 4.5

# Data Collection Range
COLLECTING_DATA_V_MIN: 0.5
COLLECTING_DATA_V_MAX: 8.0
COLLECTING_DATA_A_MIN: -1.0
COLLECTING_DATA_A_MAX: 1.0

# Noise Parameters
longitudinal_velocity_noise_amp: 0.01
longitudinal_velocity_noise_min_period: 5.0
longitudinal_velocity_noise_max_period: 20.0

acc_noise_amp: 0.01
acc_noise_min_period: 5.0
acc_noise_max_period: 20.0

steer_noise_amp: 0.01
steer_noise_min_period: 5.0
steer_noise_max_period: 20.0
54 changes: 0 additions & 54 deletions control_data_collecting_tool/config/param.yaml

This file was deleted.

Loading

0 comments on commit f3e9313

Please sign in to comment.