From a7db560481a34f86245a3b19e7489aa37fd3cd0c Mon Sep 17 00:00:00 2001
From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com>
Date: Thu, 22 Aug 2024 09:23:02 +0900
Subject: [PATCH 001/169] ci(build-and-test-differential): separate
build-and-test-differential job to composite action (#8555)
* ci(build-and-test-differential): separate build-and-test-differential job to composite action
Signed-off-by: Y.Hisaki
* fix bug
Signed-off-by: Y.Hisaki
* fix bug
Signed-off-by: Y.Hisaki
---------
Signed-off-by: Y.Hisaki
---
.../build-and-test-differential/action.yaml | 109 ++++++++++++++++++
.../build-and-test-differential.yaml | 80 ++-----------
2 files changed, 116 insertions(+), 73 deletions(-)
create mode 100644 .github/actions/build-and-test-differential/action.yaml
diff --git a/.github/actions/build-and-test-differential/action.yaml b/.github/actions/build-and-test-differential/action.yaml
new file mode 100644
index 0000000000000..3decc3f9861b1
--- /dev/null
+++ b/.github/actions/build-and-test-differential/action.yaml
@@ -0,0 +1,109 @@
+name: build-and-test-differential
+description: ""
+
+inputs:
+ rosdistro:
+ description: ""
+ required: true
+ container:
+ description: ""
+ required: true
+ container-suffix:
+ description: ""
+ required: true
+ runner:
+ description: ""
+ required: true
+ build-depends-repos:
+ description: ""
+ required: true
+ build-pre-command:
+ description: ""
+ required: true
+ codecov-token:
+ description: ""
+ required: true
+
+runs:
+ using: composite
+ steps:
+ - name: Show disk space before the tasks
+ run: df -h
+ shell: bash
+
+ - name: Show machine specs
+ run: lscpu && free -h
+ shell: bash
+
+ - name: Remove exec_depend
+ uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1
+
+ - name: Get modified packages
+ id: get-modified-packages
+ uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1
+
+ - name: Create ccache directory
+ run: |
+ mkdir -p ${CCACHE_DIR}
+ du -sh ${CCACHE_DIR} && ccache -s
+ shell: bash
+
+ - name: Attempt to restore ccache
+ uses: actions/cache/restore@v4
+ with:
+ path: |
+ /root/.ccache
+ key: ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}-${{ github.event.pull_request.base.sha }}
+ restore-keys: |
+ ccache-main-${{ runner.arch }}-${{ inputs.rosdistro }}-
+
+ - name: Show ccache stats before build
+ run: du -sh ${CCACHE_DIR} && ccache -s
+ shell: bash
+
+ - name: Export CUDA state as a variable for adding to cache key
+ run: |
+ build_type_cuda_state=nocuda
+ if [[ "${{ inputs.container-suffix }}" == "-cuda" ]]; then
+ build_type_cuda_state=cuda
+ fi
+ echo "BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" >> "${GITHUB_ENV}"
+ echo "::notice::BUILD_TYPE_CUDA_STATE=$build_type_cuda_state"
+ shell: bash
+
+ - name: Build
+ if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }}
+ uses: autowarefoundation/autoware-github-actions/colcon-build@v1
+ with:
+ rosdistro: ${{ inputs.rosdistro }}
+ target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
+ build-depends-repos: ${{ inputs.build-depends-repos }}
+ cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }}
+ build-pre-command: ${{ inputs.build-pre-command }}
+
+ - name: Show ccache stats after build
+ run: du -sh ${CCACHE_DIR} && ccache -s
+ shell: bash
+
+ - name: Test
+ id: test
+ if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }}
+ uses: autowarefoundation/autoware-github-actions/colcon-test@v1
+ with:
+ rosdistro: ${{ inputs.rosdistro }}
+ target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
+ build-depends-repos: ${{ inputs.build-depends-repos }}
+
+ - name: Upload coverage to CodeCov
+ if: ${{ steps.test.outputs.coverage-report-files != '' }}
+ uses: codecov/codecov-action@v4
+ with:
+ files: ${{ steps.test.outputs.coverage-report-files }}
+ fail_ci_if_error: false
+ verbose: true
+ flags: differential
+ token: ${{ inputs.codecov-token }}
+
+ - name: Show disk space after the tasks
+ run: df -h
+ shell: bash
diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml
index 78c21477c2588..48d432861f1de 100644
--- a/.github/workflows/build-and-test-differential.yaml
+++ b/.github/workflows/build-and-test-differential.yaml
@@ -48,6 +48,7 @@ jobs:
steps:
- name: Set PR fetch depth
run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}"
+ shell: bash
- name: Checkout PR branch and all PR commits
uses: actions/checkout@v4
@@ -55,83 +56,16 @@ jobs:
ref: ${{ github.event.pull_request.head.sha }}
fetch-depth: ${{ env.PR_FETCH_DEPTH }}
- - name: Show disk space before the tasks
- run: df -h
-
- - name: Show machine specs
- run: lscpu && free -h
-
- - name: Remove exec_depend
- uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1
-
- - name: Get modified packages
- id: get-modified-packages
- uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1
-
- - name: Create ccache directory
- run: |
- mkdir -p ${CCACHE_DIR}
- du -sh ${CCACHE_DIR} && ccache -s
- shell: bash
-
- - name: Attempt to restore ccache
- uses: actions/cache/restore@v4
- with:
- path: |
- /root/.ccache
- key: ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}-${{ github.event.pull_request.base.sha }}
- restore-keys: |
- ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}-
-
- - name: Show ccache stats before build
- run: du -sh ${CCACHE_DIR} && ccache -s
- shell: bash
-
- - name: Export CUDA state as a variable for adding to cache key
- run: |
- build_type_cuda_state=nocuda
- if [[ "${{ matrix.container-suffix }}" == "-cuda" ]]; then
- build_type_cuda_state=cuda
- fi
- echo "BUILD_TYPE_CUDA_STATE=$build_type_cuda_state" >> "${GITHUB_ENV}"
- echo "::notice::BUILD_TYPE_CUDA_STATE=$build_type_cuda_state"
- shell: bash
-
- - name: Build
- if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }}
- uses: autowarefoundation/autoware-github-actions/colcon-build@v1
+ - name: Run build-and-test-differential action
+ uses: ./.github/actions/build-and-test-differential
with:
rosdistro: ${{ matrix.rosdistro }}
- target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
+ container: ${{ matrix.container }}
+ container-suffix: ${{ matrix.container-suffix }}
+ runner: ${{ matrix.runner }}
build-depends-repos: ${{ matrix.build-depends-repos }}
- cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }}
build-pre-command: ${{ matrix.build-pre-command }}
-
- - name: Show ccache stats after build
- run: du -sh ${CCACHE_DIR} && ccache -s
- shell: bash
-
- - name: Test
- id: test
- if: ${{ steps.get-modified-packages.outputs.modified-packages != '' }}
- uses: autowarefoundation/autoware-github-actions/colcon-test@v1
- with:
- rosdistro: ${{ matrix.rosdistro }}
- target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
- build-depends-repos: ${{ matrix.build-depends-repos }}
-
- - name: Upload coverage to CodeCov
- if: ${{ steps.test.outputs.coverage-report-files != '' }}
- uses: codecov/codecov-action@v4
- with:
- files: ${{ steps.test.outputs.coverage-report-files }}
- fail_ci_if_error: false
- verbose: true
- flags: differential
- token: ${{ secrets.CODECOV_TOKEN }}
-
- - name: Show disk space after the tasks
- run: df -h
+ codecov-token: ${{ secrets.CODECOV_TOKEN }}
clang-tidy-differential:
needs: build-and-test-differential
From c83e3a1c47ca43bdd11c18be79a1d6a61afccf13 Mon Sep 17 00:00:00 2001
From: mkquda <168697710+mkquda@users.noreply.github.com>
Date: Thu, 22 Aug 2024 09:54:41 +0900
Subject: [PATCH 002/169] feat(freespace_planning_algorithms): implement option
for backward search from goal to start (#8091)
* refactor freespace planning algorithms
Signed-off-by: mohammad alqudah
* fix error
Signed-off-by: mohammad alqudah
* use vector instead of map for a-star node graph
Signed-off-by: mohammad alqudah
* remove unnecessary parameters
Signed-off-by: mohammad alqudah
* precompute average turning radius
Signed-off-by: mohammad alqudah
* add threshold for minimum distance between direction changes
Signed-off-by: mohammad alqudah
* apply curvature weight and change in curvature weight
Signed-off-by: mohammad alqudah
* store total cost instead of heuristic cost
Signed-off-by: mohammad alqudah
* fix reverse weight application
Signed-off-by: mohammad alqudah
* fix parameter description in README
Signed-off-by: mohammad alqudah
* implement edt map to store distance to nearest obstacle for each grid cell
Signed-off-by: mohammad alqudah
* use obstacle edt in collision check
Signed-off-by: mohammad alqudah
* add cost for distance to obstacle
Signed-off-by: mohammad alqudah
* fix formats
Signed-off-by: mohammad alqudah
* add missing include
Signed-off-by: mohammad alqudah
* refactor functions
Signed-off-by: mohammad alqudah
* add missing include
Signed-off-by: mohammad alqudah
* implement backward search option
Signed-off-by: mohammad alqudah
* precompute number of margin cells to reduce out of range vertices check necessity
Signed-off-by: mohammad alqudah
* add reset data function
Signed-off-by: mohammad alqudah
* remove unnecessary code
Signed-off-by: mohammad alqudah
* add member function set() to AstarNode struct
Signed-off-by: mohammad alqudah
* implement adaptive expansion distance
Signed-off-by: mohammad alqudah
* remove unnecessary code
Signed-off-by: mohammad alqudah
* interpolate nodes with large expansion distance
Signed-off-by: mohammad alqudah
* minor refactor
Signed-off-by: mohammad alqudah
* fix interpolation for backward search
Signed-off-by: mohammad alqudah
* ensure expansion distance is larger than grid cell diagonal
Signed-off-by: mohammad alqudah
* compute collision free distance to goal map
Signed-off-by: mohammad alqudah
* use obstacle edt when computing collision free distance map
Signed-off-by: mohammad alqudah
* minor refactor
Signed-off-by: mohammad alqudah
* fix expansion cost function
Signed-off-by: mohammad alqudah
* set distance map before setting start node
Signed-off-by: mohammad alqudah
* refactor detect collision function
Signed-off-by: mohammad alqudah
* use flag instead of enum
Signed-off-by: mohammad alqudah
* add missing variable initialization
Signed-off-by: mohammad alqudah
* remove declared but undefined function
Signed-off-by: mohammad alqudah
* refactor makePlan() function
Signed-off-by: mohammad alqudah
* remove bool return statement for void function
Signed-off-by: mohammad alqudah
* remove unnecessary checks
Signed-off-by: mohammad alqudah
* minor fix
Signed-off-by: mohammad alqudah
* refactor computeEDTMap function
Signed-off-by: mohammad alqudah
* remove unnecessary code
Signed-off-by: mohammad alqudah
* set min and max expansion distance after setting costmap
Signed-off-by: mohammad alqudah
* refactor detectCollision function
Signed-off-by: mohammad alqudah
* remove unused function
Signed-off-by: mohammad alqudah
* change default parameter values
Signed-off-by: mohammad alqudah
* add missing last waypoint
Signed-off-by: mohammad alqudah
* fix computeEDTMap function
Signed-off-by: mohammad alqudah
* rename parameter
Signed-off-by: mohammad alqudah
* use linear function for obstacle distance cost
Signed-off-by: mohammad alqudah
* fix rrtstar obstacle check
Signed-off-by: mohammad alqudah
* add public access function to get distance to nearest obstacle
Signed-off-by: mohammad alqudah
* remove redundant return statements
Signed-off-by: mohammad alqudah
* check goal pose validity before setting collision free distance map
Signed-off-by: mohammad alqudah
* declare variables as const where necessary
Signed-off-by: mohammad alqudah
* compare front and back lengths when setting min and max dimension
Signed-off-by: mohammad alqudah
* add docstring and citation for computeEDTMap function
Signed-off-by: mohammad alqudah
* transform pose to local frame in getDistanceToObstacle funcion
Signed-off-by: mohammad alqudah
* update freespace planner parameter schema
Signed-off-by: mohammad alqudah
* refactor setPath function
Signed-off-by: mohammad alqudah
* fix function setPath
Signed-off-by: mohammad alqudah
* minor refactor
Signed-off-by: mohammad alqudah
---------
Signed-off-by: mohammad alqudah
Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com>
---
planning/autoware_freespace_planner/README.md | 1 +
.../config/freespace_planner.param.yaml | 1 +
.../schema/freespace_planner.schema.json | 18 ++++-
.../abstract_algorithm.hpp | 1 +
.../astar_search.hpp | 5 +-
.../scripts/bind/astar_search_pybind.cpp | 1 +
.../scripts/example/example.py | 1 +
.../src/abstract_algorithm.cpp | 10 +++
.../src/astar_search.cpp | 66 ++++++++++++-------
.../test_freespace_planning_algorithms.cpp | 5 +-
.../config/goal_planner.param.yaml | 1 +
.../src/manager.cpp | 2 +
.../config/start_planner.param.yaml | 1 +
.../src/manager.cpp | 2 +
14 files changed, 87 insertions(+), 28 deletions(-)
diff --git a/planning/autoware_freespace_planner/README.md b/planning/autoware_freespace_planner/README.md
index 179bb55186c21..db48154ffa214 100644
--- a/planning/autoware_freespace_planner/README.md
+++ b/planning/autoware_freespace_planner/README.md
@@ -77,6 +77,7 @@ None
| Parameter | Type | Description |
| --------------------------- | ------ | ------------------------------------------------------- |
+| `search_method` | string | method of searching, start to goal or vice versa |
| `only_behind_solutions` | bool | whether restricting the solutions to be behind the goal |
| `use_back` | bool | whether using backward trajectory |
| `adapt_expansion_distance` | bool | if true, adapt expansion distance based on environment |
diff --git a/planning/autoware_freespace_planner/config/freespace_planner.param.yaml b/planning/autoware_freespace_planner/config/freespace_planner.param.yaml
index cadce152febc2..6ea99b2c0c061 100644
--- a/planning/autoware_freespace_planner/config/freespace_planner.param.yaml
+++ b/planning/autoware_freespace_planner/config/freespace_planner.param.yaml
@@ -31,6 +31,7 @@
# -- A* search Configurations --
astar:
+ search_method: "forward" # options: forward, backward
only_behind_solutions: false
use_back: true
adapt_expansion_distance: true
diff --git a/planning/autoware_freespace_planner/schema/freespace_planner.schema.json b/planning/autoware_freespace_planner/schema/freespace_planner.schema.json
index 92a2274347371..4494878849897 100644
--- a/planning/autoware_freespace_planner/schema/freespace_planner.schema.json
+++ b/planning/autoware_freespace_planner/schema/freespace_planner.schema.json
@@ -120,6 +120,12 @@
"astar": {
"type": "object",
"properties": {
+ "search_method": {
+ "type": "string",
+ "enum": ["forward", "backward"],
+ "default": "forward",
+ "description": "Search method to use, options: forward, backward."
+ },
"only_behind_solutions": {
"type": "boolean",
"default": false,
@@ -130,6 +136,11 @@
"default": true,
"description": "Allow reverse motion in A* search."
},
+ "adapt_expansion_distance": {
+ "type": "boolean",
+ "default": true,
+ "description": "Allow varying A* expansion distance based on space configuration."
+ },
"expansion_distance": {
"type": "number",
"default": 0.5,
@@ -143,7 +154,12 @@
"smoothness_weight": {
"type": "number",
"default": 0.5,
- "description": "Weight for the smoothness heuristic in A* search."
+ "description": "Weight for the smoothness (change in curvature) in A* search."
+ },
+ "obstacle_distance_weight": {
+ "type": "number",
+ "default": 0.5,
+ "description": "Weight for distance to obstacle in A* search."
}
},
"required": [
diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp
index cbf835df3b6c6..911144f3796e5 100644
--- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp
+++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp
@@ -164,6 +164,7 @@ class AbstractPlanningAlgorithm
const geometry_msgs::msg::Pose & start_pose, const geometry_msgs::msg::Pose & goal_pose) = 0;
virtual bool hasObstacleOnTrajectory(const geometry_msgs::msg::PoseArray & trajectory) const;
const PlannerWaypoints & getWaypoints() const { return waypoints_; }
+ double getDistanceToObstacle(const geometry_msgs::msg::Pose & pose) const;
virtual ~AbstractPlanningAlgorithm() {}
diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
index cbdbb9d4c3fb3..8ac7c60e7ca4f 100644
--- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
+++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
@@ -41,6 +41,7 @@ enum class NodeStatus : uint8_t { None, Open, Closed };
struct AstarParam
{
// base configs
+ std::string search_method;
bool only_behind_solutions; // solutions should be behind the goal
bool use_back; // backward search
bool adapt_expansion_distance;
@@ -99,6 +100,7 @@ class AstarSearch : public AbstractPlanningAlgorithm
: AstarSearch(
planner_common_param, collision_vehicle_shape,
AstarParam{
+ node.declare_parameter("astar.search_method"),
node.declare_parameter("astar.only_behind_solutions"),
node.declare_parameter("astar.use_back"),
node.declare_parameter("astar.adapt_expansion_distance"),
@@ -125,7 +127,7 @@ class AstarSearch : public AbstractPlanningAlgorithm
void expandNodes(AstarNode & current_node, const bool is_back = false);
void resetData();
void setPath(const AstarNode & goal);
- bool setStartNode();
+ void setStartNode();
double estimateCost(const Pose & pose, const IndexXYT & index) const;
bool isGoal(const AstarNode & node) const;
Pose node2pose(const AstarNode & node) const;
@@ -156,6 +158,7 @@ class AstarSearch : public AbstractPlanningAlgorithm
double avg_turning_radius_;
double min_expansion_dist_;
double max_expansion_dist_;
+ bool is_backward_search_;
// the following constexpr values were found to be best by trial and error, through multiple
// tests, and are not expected to be changed regularly, therefore they were not made into ros
diff --git a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp
index 40b16f71d5fe7..1c04fd65447b2 100644
--- a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp
+++ b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp
@@ -111,6 +111,7 @@ PYBIND11_MODULE(autoware_freespace_planning_algorithms_pybind, p)
auto pyAstarParam =
py::class_(p, "AstarParam", py::dynamic_attr())
.def(py::init<>())
+ .def_readwrite("search_method", &freespace_planning_algorithms::AstarParam::search_method)
.def_readwrite(
"only_behind_solutions", &freespace_planning_algorithms::AstarParam::only_behind_solutions)
.def_readwrite("use_back", &freespace_planning_algorithms::AstarParam::use_back)
diff --git a/planning/autoware_freespace_planning_algorithms/scripts/example/example.py b/planning/autoware_freespace_planning_algorithms/scripts/example/example.py
index 28c505fbaae02..b4af9ed87a3b9 100644
--- a/planning/autoware_freespace_planning_algorithms/scripts/example/example.py
+++ b/planning/autoware_freespace_planning_algorithms/scripts/example/example.py
@@ -44,6 +44,7 @@
# -- A* search Configurations --
astar_param = fp.AstarParam()
+astar_param.search_method = "forward"
astar_param.only_behind_solutions = False
astar_param.use_back = True
astar_param.adapt_expansion_distance = True
diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp
index 380eafb745062..97fd93e31d5cd 100644
--- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp
+++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp
@@ -138,6 +138,16 @@ void AbstractPlanningAlgorithm::setMap(const nav_msgs::msg::OccupancyGrid & cost
std::hypot(0.5 * collision_vehicle_shape_.width, base2front) / costmap_.info.resolution);
}
+double AbstractPlanningAlgorithm::getDistanceToObstacle(const geometry_msgs::msg::Pose & pose) const
+{
+ const auto local_pose = global2local(costmap_, pose);
+ const auto index = pose2index(costmap_, local_pose, planner_common_param_.theta_size);
+ if (indexToId(index) >= static_cast(edt_map_.size())) {
+ return std::numeric_limits::max();
+ }
+ return getObstacleEDT(index);
+}
+
void AbstractPlanningAlgorithm::computeEDTMap()
{
const int height = costmap_.info.height;
diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
index fe87011273c1b..b0be1da75caec 100644
--- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
+++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
@@ -29,6 +29,7 @@
#include
#endif
+#include
#include
namespace autoware::freespace_planning_algorithms
@@ -83,6 +84,8 @@ AstarSearch::AstarSearch(
avg_turning_radius_ =
kinematic_bicycle_model::getTurningRadius(collision_vehicle_shape_.base_length, avg_steering);
+ is_backward_search_ = astar_param_.search_method == "backward";
+
min_expansion_dist_ = astar_param_.expansion_distance;
max_expansion_dist_ = collision_vehicle_shape_.base_length * base_length_max_expansion_factor_;
}
@@ -104,15 +107,15 @@ bool AstarSearch::makePlan(const Pose & start_pose, const Pose & goal_pose)
start_pose_ = global2local(costmap_, start_pose);
goal_pose_ = global2local(costmap_, goal_pose);
- if (detectCollision(goal_pose_)) {
- throw std::logic_error("Invalid goal pose");
+ if (detectCollision(start_pose_) || detectCollision(goal_pose_)) {
+ throw std::logic_error("Invalid start or goal pose");
}
+ if (is_backward_search_) std::swap(start_pose_, goal_pose_);
+
setCollisionFreeDistanceMap();
- if (!setStartNode()) {
- throw std::logic_error("Invalid start pose");
- }
+ setStartNode();
if (!search()) {
throw std::logic_error("HA* failed to find path to goal");
@@ -174,12 +177,9 @@ void AstarSearch::setCollisionFreeDistanceMap()
}
}
-bool AstarSearch::setStartNode()
+void AstarSearch::setStartNode()
{
const auto index = pose2index(costmap_, start_pose_, planner_common_param_.theta_size);
-
- if (detectCollision(index)) return false;
-
// Set start node
AstarNode * start_node = &graph_[getKey(index)];
start_node->set(start_pose_, 0.0, estimateCost(start_pose_, index), 0, false);
@@ -191,8 +191,6 @@ bool AstarSearch::setStartNode()
// Push start node to openlist
openlist_.push(start_node);
-
- return true;
}
double AstarSearch::estimateCost(const Pose & pose, const IndexXYT & index) const
@@ -242,7 +240,8 @@ bool AstarSearch::search()
void AstarSearch::expandNodes(AstarNode & current_node, const bool is_back)
{
const auto current_pose = node2pose(current_node);
- double distance = getExpansionDistance(current_node) * (is_back ? -1.0 : 1.0);
+ const double direction = (is_back == is_backward_search_) ? 1.0 : -1.0;
+ const double distance = getExpansionDistance(current_node) * direction;
int steering_index = -1 * planner_common_param_.turning_steps;
for (; steering_index <= planner_common_param_.turning_steps; ++steering_index) {
// skip expansion back to parent
@@ -333,46 +332,65 @@ void AstarSearch::setPath(const AstarNode & goal_node)
header.stamp = rclcpp::Clock(RCL_ROS_TIME).now();
header.frame_id = costmap_.header.frame_id;
- waypoints_.header = header;
- waypoints_.waypoints.clear();
-
// From the goal node to the start node
const AstarNode * node = &goal_node;
+ std::vector waypoints;
+
geometry_msgs::msg::PoseStamped pose;
pose.header = header;
- const auto interpolate = [this, &pose](const AstarNode & node) {
+ const auto interpolate = [this, &waypoints, &pose](const AstarNode & node) {
if (node.parent == nullptr || !astar_param_.adapt_expansion_distance) return;
const auto parent_pose = node2pose(*node.parent);
const double distance_2d = calcDistance2d(node2pose(node), parent_pose);
const int n = static_cast(distance_2d / min_expansion_dist_);
for (int i = 1; i < n; ++i) {
- const double dist = ((distance_2d * i) / n) * (node.is_back ? -1.0 : 1.0);
+ const double dist =
+ ((distance_2d * i) / n) * (node.is_back == is_backward_search_ ? 1.0 : -1.0);
const double steering = node.steering_index * steering_resolution_;
const auto local_pose = kinematic_bicycle_model::getPose(
parent_pose, collision_vehicle_shape_.base_length, steering, dist);
pose.pose = local2global(costmap_, local_pose);
- waypoints_.waypoints.push_back({pose, node.is_back});
+ waypoints.push_back({pose, node.is_back});
}
};
// push astar nodes poses
while (node != nullptr) {
pose.pose = local2global(costmap_, node2pose(*node));
- waypoints_.waypoints.push_back({pose, node->is_back});
+ waypoints.push_back({pose, node->is_back});
interpolate(*node);
// To the next node
node = node->parent;
}
- // Reverse the vector to be start to goal order
- std::reverse(waypoints_.waypoints.begin(), waypoints_.waypoints.end());
+ if (waypoints.empty()) return;
- // Update first point direction
- if (waypoints_.waypoints.size() > 1) {
- waypoints_.waypoints.at(0).is_back = waypoints_.waypoints.at(1).is_back;
+ if (waypoints.size() > 1) waypoints.back().is_back = waypoints.rbegin()[1].is_back;
+
+ if (!is_backward_search_) {
+ // Reverse the vector to be start to goal order
+ std::reverse(waypoints.begin(), waypoints.end());
+ }
+
+ waypoints_.header = header;
+ waypoints_.waypoints.clear();
+
+ for (size_t i = 0; i < waypoints.size() - 1; ++i) {
+ const auto & current = waypoints[i];
+ const auto & next = waypoints[i + 1];
+
+ waypoints_.waypoints.push_back(current);
+
+ if (current.is_back != next.is_back) {
+ waypoints_.waypoints.push_back(
+ {is_backward_search_ ? next.pose : current.pose,
+ is_backward_search_ ? current.is_back : next.is_back});
+ }
}
+
+ waypoints_.waypoints.push_back(waypoints.back());
}
bool AstarSearch::isGoal(const AstarNode & node) const
diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp
index 7284a8dcffc44..82806bb500b0e 100644
--- a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp
+++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp
@@ -209,6 +209,7 @@ std::unique_ptr configure_astar(bool use_multi)
}
// configure astar param
+ const std::string search_method = "forward";
const bool only_behind_solutions = false;
const bool use_back = true;
const bool adapt_expansion_distance = true;
@@ -217,8 +218,8 @@ std::unique_ptr configure_astar(bool use_multi)
const double smoothness_weight = 0.5;
const double obstacle_distance_weight = 1.7;
const auto astar_param = fpa::AstarParam{
- only_behind_solutions, use_back, adapt_expansion_distance, expansion_distance,
- distance_heuristic_weight, smoothness_weight, obstacle_distance_weight};
+ search_method, only_behind_solutions, use_back, adapt_expansion_distance,
+ expansion_distance, distance_heuristic_weight, smoothness_weight, obstacle_distance_weight};
auto algo = std::make_unique(planner_common_param, vehicle_shape, astar_param);
return algo;
diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml
index d3d23ae69dc1a..b40214bf2e89e 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml
+++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/config/goal_planner.param.yaml
@@ -106,6 +106,7 @@
obstacle_threshold: 30
# -- A* search Configurations --
astar:
+ search_method: "forward" # options: forward, backward
only_behind_solutions: false
use_back: false
distance_heuristic_weight: 1.0
diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
index 805e91f739a6a..9f146f0ad73d0 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
@@ -235,6 +235,7 @@ void GoalPlannerModuleManager::init(rclcpp::Node * node)
// freespace parking astar
{
const std::string ns = base_ns + "pull_over.freespace_parking.astar.";
+ p.astar_parameters.search_method = node->declare_parameter(ns + "search_method");
p.astar_parameters.only_behind_solutions =
node->declare_parameter(ns + "only_behind_solutions");
p.astar_parameters.use_back = node->declare_parameter(ns + "use_back");
@@ -623,6 +624,7 @@ void GoalPlannerModuleManager::updateModuleParams(
// freespace parking astar
{
const std::string ns = base_ns + "pull_over.freespace_parking.astar.";
+ updateParam(parameters, ns + "search_method", p->astar_parameters.search_method);
updateParam(
parameters, ns + "only_behind_solutions", p->astar_parameters.only_behind_solutions);
updateParam(parameters, ns + "use_back", p->astar_parameters.use_back);
diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml
index 851e96f7a265c..499f713a3d65b 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml
+++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/config/start_planner.param.yaml
@@ -77,6 +77,7 @@
obstacle_threshold: 30
# -- A* search Configurations --
astar:
+ search_method: "forward" # options: forward, backward
only_behind_solutions: false
use_back: false
distance_heuristic_weight: 1.0
diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp
index 23817ee081501..193f88d212842 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/manager.cpp
@@ -167,6 +167,7 @@ void StartPlannerModuleManager::init(rclcpp::Node * node)
// freespace planner astar
{
const std::string ns = "start_planner.freespace_planner.astar.";
+ p.astar_parameters.search_method = node->declare_parameter(ns + "search_method");
p.astar_parameters.only_behind_solutions =
node->declare_parameter(ns + "only_behind_solutions");
p.astar_parameters.use_back = node->declare_parameter(ns + "use_back");
@@ -501,6 +502,7 @@ void StartPlannerModuleManager::updateModuleParams(
{
const std::string ns = "start_planner.freespace_planner.astar.";
+ updateParam(parameters, ns + "search_method", p->astar_parameters.search_method);
updateParam(parameters, ns + "use_back", p->astar_parameters.use_back);
updateParam(
parameters, ns + "only_behind_solutions", p->astar_parameters.only_behind_solutions);
From 9202499373ea7ada6ac1b7e31bf519971226edb7 Mon Sep 17 00:00:00 2001
From: Masaki Baba
Date: Thu, 22 Aug 2024 13:03:29 +0900
Subject: [PATCH 003/169] refactor(localization_error_monitor)!: prefix package
and namespace with autoware (#8423)
add autoware_ prefix
Signed-off-by: a-maumau
---
.github/CODEOWNERS | 2 +-
.../localization_error_monitor.launch.xml | 2 +-
.../CMakeLists.txt | 6 +--
.../README.md | 6 +--
.../localization_error_monitor.param.yaml | 0
.../localization_error_monitor.launch.xml | 9 ++++
.../media/diagnostics.png | Bin
.../package.xml | 2 +-
.../localization_error_monitor.schema.json | 0
.../src/diagnostics.cpp | 5 +++
.../src}/diagnostics.hpp | 9 ++--
.../src/localization_error_monitor.cpp | 10 +++--
.../src}/localization_error_monitor.hpp | 10 +++--
.../test/test_diagnostics.cpp | 41 ++++++++++--------
.../localization_error_monitor.launch.xml | 9 ----
15 files changed, 66 insertions(+), 45 deletions(-)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/CMakeLists.txt (87%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/README.md (74%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/config/localization_error_monitor.param.yaml (100%)
create mode 100644 localization/autoware_localization_error_monitor/launch/localization_error_monitor.launch.xml
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/media/diagnostics.png (100%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/package.xml (96%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/schema/localization_error_monitor.schema.json (100%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/src/diagnostics.cpp (96%)
rename localization/{localization_error_monitor/include/localization_error_monitor => autoware_localization_error_monitor/src}/diagnostics.hpp (86%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/src/localization_error_monitor.cpp (92%)
rename localization/{localization_error_monitor/include/localization_error_monitor => autoware_localization_error_monitor/src}/localization_error_monitor.hpp (88%)
rename localization/{localization_error_monitor => autoware_localization_error_monitor}/test/test_diagnostics.cpp (73%)
delete mode 100644 localization/localization_error_monitor/launch/localization_error_monitor.launch.xml
diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 0f98b3a2ce884..08fa500a8d546 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -88,7 +88,7 @@ localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier
localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp
localization/autoware_geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
-localization/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
+localization/autoware_localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_estimator_arbiter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
diff --git a/launch/tier4_localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml b/launch/tier4_localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml
index 4caefed02584a..ceff1f3fdcdb7 100644
--- a/launch/tier4_localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml
+++ b/launch/tier4_localization_launch/launch/localization_error_monitor/localization_error_monitor.launch.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/localization/localization_error_monitor/CMakeLists.txt b/localization/autoware_localization_error_monitor/CMakeLists.txt
similarity index 87%
rename from localization/localization_error_monitor/CMakeLists.txt
rename to localization/autoware_localization_error_monitor/CMakeLists.txt
index c27e51e6e0359..93cfb7ba7a0d9 100644
--- a/localization/localization_error_monitor/CMakeLists.txt
+++ b/localization/autoware_localization_error_monitor/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
-project(localization_error_monitor)
+project(autoware_localization_error_monitor)
find_package(autoware_cmake REQUIRED)
autoware_package()
@@ -10,7 +10,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)
rclcpp_components_register_node(${PROJECT_NAME}
- PLUGIN "LocalizationErrorMonitor"
+ PLUGIN "autoware::localization_error_monitor::LocalizationErrorMonitor"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
@@ -20,7 +20,7 @@ if(BUILD_TESTING)
get_filename_component(filename ${filepath} NAME)
string(REGEX REPLACE ".cpp" "" test_name ${filename})
ament_add_gtest(${test_name} ${filepath})
- target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include)
+ target_include_directories(${test_name} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/src)
target_link_libraries(${test_name} ${PROJECT_NAME})
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
endfunction()
diff --git a/localization/localization_error_monitor/README.md b/localization/autoware_localization_error_monitor/README.md
similarity index 74%
rename from localization/localization_error_monitor/README.md
rename to localization/autoware_localization_error_monitor/README.md
index 8dc82f09f3d07..9ea1eb5b269d9 100644
--- a/localization/localization_error_monitor/README.md
+++ b/localization/autoware_localization_error_monitor/README.md
@@ -1,4 +1,4 @@
-# localization_error_monitor
+# autoware_localization_error_monitor
## Purpose
@@ -6,7 +6,7 @@
-localization_error_monitor is a package for diagnosing localization errors by monitoring uncertainty of the localization results.
+autoware_localization_error_monitor is a package for diagnosing localization errors by monitoring uncertainty of the localization results.
The package monitors the following two values:
- size of long radius of confidence ellipse
@@ -29,4 +29,4 @@ The package monitors the following two values:
## Parameters
-{{ json_to_markdown("localization/localization_error_monitor/schema/localization_error_monitor.schema.json") }}
+{{ json_to_markdown("localization/autoware_localization_error_monitor/schema/localization_error_monitor.schema.json") }}
diff --git a/localization/localization_error_monitor/config/localization_error_monitor.param.yaml b/localization/autoware_localization_error_monitor/config/localization_error_monitor.param.yaml
similarity index 100%
rename from localization/localization_error_monitor/config/localization_error_monitor.param.yaml
rename to localization/autoware_localization_error_monitor/config/localization_error_monitor.param.yaml
diff --git a/localization/autoware_localization_error_monitor/launch/localization_error_monitor.launch.xml b/localization/autoware_localization_error_monitor/launch/localization_error_monitor.launch.xml
new file mode 100644
index 0000000000000..3ac61a8b45570
--- /dev/null
+++ b/localization/autoware_localization_error_monitor/launch/localization_error_monitor.launch.xml
@@ -0,0 +1,9 @@
+
+
+
+
+
+
+
+
+
diff --git a/localization/localization_error_monitor/media/diagnostics.png b/localization/autoware_localization_error_monitor/media/diagnostics.png
similarity index 100%
rename from localization/localization_error_monitor/media/diagnostics.png
rename to localization/autoware_localization_error_monitor/media/diagnostics.png
diff --git a/localization/localization_error_monitor/package.xml b/localization/autoware_localization_error_monitor/package.xml
similarity index 96%
rename from localization/localization_error_monitor/package.xml
rename to localization/autoware_localization_error_monitor/package.xml
index c4fa77ce85a6b..426b0d6b6c432 100644
--- a/localization/localization_error_monitor/package.xml
+++ b/localization/autoware_localization_error_monitor/package.xml
@@ -1,7 +1,7 @@
- localization_error_monitor
+ autoware_localization_error_monitor
0.1.0
ros node for monitoring localization error
Yamato Ando
diff --git a/localization/localization_error_monitor/schema/localization_error_monitor.schema.json b/localization/autoware_localization_error_monitor/schema/localization_error_monitor.schema.json
similarity index 100%
rename from localization/localization_error_monitor/schema/localization_error_monitor.schema.json
rename to localization/autoware_localization_error_monitor/schema/localization_error_monitor.schema.json
diff --git a/localization/localization_error_monitor/src/diagnostics.cpp b/localization/autoware_localization_error_monitor/src/diagnostics.cpp
similarity index 96%
rename from localization/localization_error_monitor/src/diagnostics.cpp
rename to localization/autoware_localization_error_monitor/src/diagnostics.cpp
index e6b9da8fc4a97..ef7f0faf12373 100644
--- a/localization/localization_error_monitor/src/diagnostics.cpp
+++ b/localization/autoware_localization_error_monitor/src/diagnostics.cpp
@@ -12,11 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "diagnostics.hpp"
+
#include
#include
#include
+namespace autoware::localization_error_monitor
+{
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size)
{
@@ -92,3 +96,4 @@ diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(
return merged_stat;
}
+} // namespace autoware::localization_error_monitor
diff --git a/localization/localization_error_monitor/include/localization_error_monitor/diagnostics.hpp b/localization/autoware_localization_error_monitor/src/diagnostics.hpp
similarity index 86%
rename from localization/localization_error_monitor/include/localization_error_monitor/diagnostics.hpp
rename to localization/autoware_localization_error_monitor/src/diagnostics.hpp
index b1da87128bee5..bd92c28daad78 100644
--- a/localization/localization_error_monitor/include/localization_error_monitor/diagnostics.hpp
+++ b/localization/autoware_localization_error_monitor/src/diagnostics.hpp
@@ -12,14 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
-#define LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
+#ifndef DIAGNOSTICS_HPP_
+#define DIAGNOSTICS_HPP_
#include
#include
#include
+namespace autoware::localization_error_monitor
+{
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy(
const double ellipse_size, const double warn_ellipse_size, const double error_ellipse_size);
diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direction(
@@ -27,5 +29,6 @@ diagnostic_msgs::msg::DiagnosticStatus check_localization_accuracy_lateral_direc
diagnostic_msgs::msg::DiagnosticStatus merge_diagnostic_status(
const std::vector & stat_array);
+} // namespace autoware::localization_error_monitor
-#endif // LOCALIZATION_ERROR_MONITOR__DIAGNOSTICS_HPP_
+#endif // DIAGNOSTICS_HPP_
diff --git a/localization/localization_error_monitor/src/localization_error_monitor.cpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp
similarity index 92%
rename from localization/localization_error_monitor/src/localization_error_monitor.cpp
rename to localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp
index 44223b0fd1670..fb96a55dd0dc1 100644
--- a/localization/localization_error_monitor/src/localization_error_monitor.cpp
+++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp
@@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "localization_error_monitor/localization_error_monitor.hpp"
+#include "localization_error_monitor.hpp"
-#include "localization_error_monitor/diagnostics.hpp"
+#include "diagnostics.hpp"
#include
@@ -31,7 +31,10 @@
#include
#include
#include
+#include
+namespace autoware::localization_error_monitor
+{
LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & options)
: Node("localization_error_monitor", options)
{
@@ -84,6 +87,7 @@ void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr i
diag_msg.status.push_back(diag_merged_status);
diag_pub_->publish(diag_msg);
}
+} // namespace autoware::localization_error_monitor
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(LocalizationErrorMonitor)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::localization_error_monitor::LocalizationErrorMonitor)
diff --git a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp
similarity index 88%
rename from localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp
rename to localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp
index 0f293e4d31cac..919951bca3998 100644
--- a/localization/localization_error_monitor/include/localization_error_monitor/localization_error_monitor.hpp
+++ b/localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
-#define LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
+#ifndef LOCALIZATION_ERROR_MONITOR_HPP_
+#define LOCALIZATION_ERROR_MONITOR_HPP_
#include "localization_util/covariance_ellipse.hpp"
@@ -27,6 +27,8 @@
#include
+namespace autoware::localization_error_monitor
+{
class LocalizationErrorMonitor : public rclcpp::Node
{
private:
@@ -50,4 +52,6 @@ class LocalizationErrorMonitor : public rclcpp::Node
public:
explicit LocalizationErrorMonitor(const rclcpp::NodeOptions & options);
};
-#endif // LOCALIZATION_ERROR_MONITOR__LOCALIZATION_ERROR_MONITOR_HPP_
+} // namespace autoware::localization_error_monitor
+
+#endif // LOCALIZATION_ERROR_MONITOR_HPP_
diff --git a/localization/localization_error_monitor/test/test_diagnostics.cpp b/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp
similarity index 73%
rename from localization/localization_error_monitor/test/test_diagnostics.cpp
rename to localization/autoware_localization_error_monitor/test/test_diagnostics.cpp
index 12515687e7a98..1cc5640d78290 100644
--- a/localization/localization_error_monitor/test/test_diagnostics.cpp
+++ b/localization/autoware_localization_error_monitor/test/test_diagnostics.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "localization_error_monitor/diagnostics.hpp"
+#include "diagnostics.hpp"
#include
@@ -24,23 +24,28 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracy)
const double error_ellipse_size = 1.0;
double ellipse_size = 0.0;
- stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
+ stat = autoware::localization_error_monitor::check_localization_accuracy(
+ ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
ellipse_size = 0.7;
- stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
+ stat = autoware::localization_error_monitor::check_localization_accuracy(
+ ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
ellipse_size = 0.8;
- stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
+ stat = autoware::localization_error_monitor::check_localization_accuracy(
+ ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
ellipse_size = 0.9;
- stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
+ stat = autoware::localization_error_monitor::check_localization_accuracy(
+ ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
ellipse_size = 1.0;
- stat = check_localization_accuracy(ellipse_size, warn_ellipse_size, error_ellipse_size);
+ stat = autoware::localization_error_monitor::check_localization_accuracy(
+ ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
}
@@ -52,27 +57,27 @@ TEST(TestLocalizationErrorMonitorDiagnostics, CheckLocalizationAccuracyLateralDi
const double error_ellipse_size = 0.3;
double ellipse_size = 0.0;
- stat = check_localization_accuracy_lateral_direction(
+ stat = autoware::localization_error_monitor::check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
ellipse_size = 0.24;
- stat = check_localization_accuracy_lateral_direction(
+ stat = autoware::localization_error_monitor::check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
ellipse_size = 0.25;
- stat = check_localization_accuracy_lateral_direction(
+ stat = autoware::localization_error_monitor::check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
ellipse_size = 0.29;
- stat = check_localization_accuracy_lateral_direction(
+ stat = autoware::localization_error_monitor::check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
ellipse_size = 0.3;
- stat = check_localization_accuracy_lateral_direction(
+ stat = autoware::localization_error_monitor::check_localization_accuracy_lateral_direction(
ellipse_size, warn_ellipse_size, error_ellipse_size);
EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
}
@@ -86,7 +91,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(1).message = "OK";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK);
EXPECT_EQ(merged_stat.message, "OK");
@@ -94,7 +99,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK;
stat_array.at(1).message = "OK";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN0");
@@ -102,7 +107,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(1).message = "WARN1";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN1");
@@ -110,7 +115,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
stat_array.at(1).message = "WARN1";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN);
EXPECT_EQ(merged_stat.message, "WARN0; WARN1");
@@ -118,7 +123,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "OK";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "ERROR1");
@@ -126,7 +131,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "WARN0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "WARN0; ERROR1");
@@ -134,7 +139,7 @@ TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus)
stat_array.at(0).message = "ERROR0";
stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
stat_array.at(1).message = "ERROR1";
- merged_stat = merge_diagnostic_status(stat_array);
+ merged_stat = autoware::localization_error_monitor::merge_diagnostic_status(stat_array);
EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR);
EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1");
}
diff --git a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml b/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml
deleted file mode 100644
index ad3e8beff92ab..0000000000000
--- a/localization/localization_error_monitor/launch/localization_error_monitor.launch.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
-
-
-
-
-
From d87301c1e5273dcf7adbb60d3a6d34359cbce93f Mon Sep 17 00:00:00 2001
From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com>
Date: Thu, 22 Aug 2024 13:23:52 +0900
Subject: [PATCH 004/169] fix(lane_change): modify lane change requested
condition (#8510)
* modify lane change requested condition
Signed-off-by: Muhammad Zulfaqar Azmi
* Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com>
* style(pre-commit): autofix
* fix docstring
Signed-off-by: Muhammad Zulfaqar Azmi
---------
Signed-off-by: Muhammad Zulfaqar Azmi
Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
---
.../utils/calculation.hpp | 38 ++++++++++++++++++
.../src/scene.cpp | 12 +++++-
.../src/utils/calculation.cpp | 40 +++++++++++++++++++
3 files changed, 89 insertions(+), 1 deletion(-)
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp
index 6c48445b47567..66c454f795ebb 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp
@@ -75,6 +75,44 @@ double calc_stopping_distance(const LCParamPtr & lc_param_ptr);
double calc_dist_to_last_fit_width(
const lanelet::ConstLanelets lanelets, const Pose & src_pose,
const BehaviorPathPlannerParameters & bpp_param, const double margin = 0.1);
+
+/**
+ * @brief Calculates the maximum preparation longitudinal distance for lane change.
+ *
+ * This function computes the maximum distance that the ego vehicle can travel during
+ * the preparation phase of a lane change. The distance is calculated as the product
+ * of the maximum lane change preparation duration and the maximum velocity of the ego vehicle.
+ *
+ * @param common_data_ptr Shared pointer to a CommonData structure, which should include:
+ * - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change
+ * preparation.
+ * - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle.
+ *
+ * @return The maximum preparation longitudinal distance in meters.
+ */
+double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr);
+
+/**
+ * @brief Calculates the distance from the ego vehicle to the start of the target lanes.
+ *
+ * This function computes the shortest distance from the current position of the ego vehicle
+ * to the start of the target lanes by measuring the arc length to the front points of
+ * the left and right boundaries of the target lane. If the target lanes are empty or other
+ * required data is unavailable, the function returns numeric_limits::max() preventing lane
+ * change being executed.
+ *
+ * @param common_data_ptr Shared pointer to a CommonData structure, which should include:
+ * - `route_handler_ptr`: Pointer to the route handler that manages the route.
+ * - Other necessary parameters for ego vehicle positioning.
+ * @param current_lanes The set of lanelets representing the current lanes of the ego vehicle.
+ * @param target_lanes The set of lanelets representing the target lanes for lane changing.
+ *
+ * @return The distance from the ego vehicle to the start of the target lanes in meters,
+ * or numeric_limits::max() if the target lanes are empty or data is unavailable.
+ */
+double calc_ego_dist_to_lanes_start(
+ const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes,
+ const lanelet::ConstLanelets & target_lanes);
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
index e3faf8f4293c7..c6d05f90fe138 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
@@ -152,6 +152,8 @@ std::pair NormalLaneChange::getSafePath(LaneChangePath & safe_path)
bool NormalLaneChange::isLaneChangeRequired()
{
+ universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);
+
const auto current_lanes =
utils::getCurrentLanesFromPath(prev_module_output_.path, planner_data_);
@@ -161,7 +163,15 @@ bool NormalLaneChange::isLaneChangeRequired()
const auto target_lanes = getLaneChangeLanes(current_lanes, direction_);
- return !target_lanes.empty();
+ if (target_lanes.empty()) {
+ return false;
+ }
+
+ const auto ego_dist_to_target_start =
+ calculation::calc_ego_dist_to_lanes_start(common_data_ptr_, current_lanes, target_lanes);
+ const auto maximum_prepare_length = calculation::calc_maximum_prepare_length(common_data_ptr_);
+
+ return ego_dist_to_target_start <= maximum_prepare_length;
}
bool NormalLaneChange::isStoppedAtRedTrafficLight() const
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
index 8f04395be572a..9585449b8e0e2 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
@@ -101,4 +101,44 @@ double calc_dist_to_last_fit_width(
return std::max(distance - (bpp_param.base_link2front + margin), 0.0);
}
+
+double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr)
+{
+ const auto max_prepare_duration = common_data_ptr->lc_param_ptr->lane_change_prepare_duration;
+ const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel;
+
+ return max_prepare_duration * ego_max_speed;
+}
+
+double calc_ego_dist_to_lanes_start(
+ const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes,
+ const lanelet::ConstLanelets & target_lanes)
+{
+ const auto & route_handler_ptr = common_data_ptr->route_handler_ptr;
+
+ if (!route_handler_ptr || target_lanes.empty() || current_lanes.empty()) {
+ return std::numeric_limits::max();
+ }
+
+ const auto & target_bound =
+ common_data_ptr->direction == autoware::route_handler::Direction::RIGHT
+ ? target_lanes.front().leftBound()
+ : target_lanes.front().rightBound();
+
+ if (target_bound.empty()) {
+ return std::numeric_limits::max();
+ }
+
+ const auto path =
+ route_handler_ptr->getCenterLinePath(current_lanes, 0.0, std::numeric_limits::max());
+
+ if (path.points.empty()) {
+ return std::numeric_limits::max();
+ }
+
+ const auto target_front_pt = lanelet::utils::conversion::toGeomMsgPt(target_bound.front());
+ const auto ego_position = common_data_ptr->get_ego_pose().position;
+
+ return motion_utils::calcSignedArcLength(path.points, ego_position, target_front_pt);
+}
} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
From d95cfaecd0e46cabe121a3bd3edc3f56fab2ef73 Mon Sep 17 00:00:00 2001
From: Kosuke Takeuchi
Date: Thu, 22 Aug 2024 13:59:52 +0900
Subject: [PATCH 005/169] feat(raw_vehicle_cmd_converter): add steer command
conversion with VGR (#8504)
* feat(raw_vehicle_cmd_converter): add steer command conversion with VGR
Signed-off-by: kosuke55
* make class and add test
Signed-off-by: kosuke55
* remove member vgr_coef from node
Signed-off-by: kosuke55
* update readme
Signed-off-by: kosuke55
* add svg
Signed-off-by: kosuke55
* add plot scripts
Signed-off-by: kosuke55
* Update vehicle/autoware_raw_vehicle_cmd_converter/README.md
Co-authored-by: Takamasa Horibe
* not always subscribe actuation_status
Signed-off-by: kosuke55
* add comment for using normal sub for steering status
Signed-off-by: kosuke55
---------
Signed-off-by: kosuke55
Co-authored-by: Takamasa Horibe
---
.../CMakeLists.txt | 1 +
.../README.md | 39 +-
.../raw_vehicle_cmd_converter.param.yaml | 5 +
.../figure/vgr.svg | 3541 +++++++++++++++++
.../node.hpp | 26 +-
.../vgr.hpp | 39 +
.../launch/raw_vehicle_converter.launch.xml | 4 +
.../raw_vehicle_cmd_converter.schema.json | 33 +-
.../scripts/plot_variable_gear_ratio.py | 107 +
.../src/node.cpp | 147 +-
.../src/vgr.cpp | 41 +
...est_autoware_raw_vehicle_cmd_converter.cpp | 48 +
12 files changed, 3982 insertions(+), 49 deletions(-)
create mode 100644 vehicle/autoware_raw_vehicle_cmd_converter/figure/vgr.svg
create mode 100644 vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vgr.hpp
create mode 100755 vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_variable_gear_ratio.py
create mode 100644 vehicle/autoware_raw_vehicle_cmd_converter/src/vgr.cpp
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
index fc54b302512fa..9e5b7439e1de2 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/CMakeLists.txt
@@ -10,6 +10,7 @@ ament_auto_add_library(actuation_map_converter SHARED
src/steer_map.cpp
src/csv_loader.cpp
src/pid.cpp
+ src/vgr.cpp
)
ament_auto_add_library(autoware_raw_vehicle_cmd_converter_node_component SHARED
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/README.md b/vehicle/autoware_raw_vehicle_cmd_converter/README.md
index 858db3cbaa768..1df083f5c5370 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/README.md
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/README.md
@@ -24,19 +24,42 @@ Once the acceleration map is crafted, it should be loaded when the RawVehicleCmd
For ease of calibration and adjustments to the lookup table, an auto-calibration tool is available. More information and instructions for this tool can be found [here](https://github.com/autowarefoundation/autoware.universe/blob/main/vehicle/autoware_accel_brake_map_calibrator/README.md).
+### Variable Gear Ratio (VGR)
+
+This is a gear ratio for converting tire angle to steering angle. Generally, to improve operability, the gear ratio becomes dynamically larger as the speed increases or the steering angle becomes smaller. For a certain vehicle, data was acquired and the gear ratio was approximated by the following formula.
+
+$$
+a + b \times v^2 - c \times \lvert \delta \rvert
+$$
+
+For that vehicle, the coefficients were as follows.
+
+```yaml
+vgr_coef_a: 15.713
+vgr_coef_b: 0.053
+vgr_coef_c: 0.042
+```
+
+![vgr](./figure/vgr.svg)
+
+When `convert_steer_cmd_method: "vgr"` is selected, the node receives the control command from the controller as the desired tire angle and calculates the desired steering angle to output.
+Also, when `convert_actuation_to_steering_status: true`, this node receives the `actuation_status` topic and calculates the steer tire angle from the `steer_wheel_angle` and publishes it.
+
## Input topics
-| Name | Type | Description |
-| --------------------- | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------ |
-| `~/input/control_cmd` | autoware_control_msgs::msg::Control | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. |
-| `~/input/steering"` | autoware_vehicle_msgs::msg::SteeringReport | current status of steering used for steering feed back control |
-| `~/input/odometry` | navigation_msgs::Odometry | twist topic in odometry is used. |
+| Name | Type | Description |
+| -------------------------- | ------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| `~/input/control_cmd` | autoware_control_msgs::msg::Control | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. |
+| `~/input/steering"` | autoware_vehicle_msgs::msg::SteeringReport | subscribe only when `convert_actuation_to_steering_status: false`. current status of steering used for steering feed back control |
+| `~/input/odometry` | navigation_msgs::Odometry | twist topic in odometry is used. |
+| `~/input/actuation_status` | tier4_vehicle_msgs::msg::ActuationStatus | actuation status is assumed to receive the same type of status as sent to the vehicle side. For example, if throttle/brake pedal/steer_wheel_angle is sent, the same type of status is received. In the case of steer_wheel_angle, it is used to calculate steer_tire_angle and VGR in this node. |
## Output topics
-| Name | Type | Description |
-| ------------------------ | ------------------------------------------------ | ------------------------------------------------------- |
-| `~/output/actuation_cmd` | tier4_vehicle_msgs::msg::ActuationCommandStamped | actuation command for vehicle to apply mechanical input |
+| Name | Type | Description |
+| -------------------------- | ------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------ |
+| `~/output/actuation_cmd` | tier4_vehicle_msgs::msg::ActuationCommandStamped | actuation command for vehicle to apply mechanical input |
+| `~/output/steering_status` | autoware_vehicle_msgs::msg::SteeringReport | publish only when `convert_actuation_to_steering_status: true`. steer tire angle is calculated from steer wheel angle and published. |
## Parameters
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
index b53b0d7622198..e7e503d6d7eee 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/config/raw_vehicle_cmd_converter.param.yaml
@@ -26,3 +26,8 @@
max_d: 0.0
min_d: 0.0
invalid_integration_decay: 0.97
+ convert_steer_cmd_method: "vgr" # "vgr" or "steer_map"
+ vgr_coef_a: 15.713
+ vgr_coef_b: 0.053
+ vgr_coef_c: 0.042
+ convert_actuation_to_steering_status: true
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/figure/vgr.svg b/vehicle/autoware_raw_vehicle_cmd_converter/figure/vgr.svg
new file mode 100644
index 0000000000000..51bf3e56d2e6a
--- /dev/null
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/figure/vgr.svg
@@ -0,0 +1,3541 @@
+
+
+
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
index 181b7926337dc..b5e13985c036e 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/node.hpp
@@ -21,6 +21,7 @@
#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/vgr.hpp"
#include
@@ -30,6 +31,7 @@
#include
#include
#include
+#include
#include
#include
@@ -40,6 +42,7 @@ namespace autoware::raw_vehicle_cmd_converter
using Control = autoware_control_msgs::msg::Control;
using tier4_debug_msgs::msg::Float32MultiArrayStamped;
using tier4_vehicle_msgs::msg::ActuationCommandStamped;
+using tier4_vehicle_msgs::msg::ActuationStatusStamped;
using TwistStamped = geometry_msgs::msg::TwistStamped;
using Odometry = nav_msgs::msg::Odometry;
using Steering = autoware_vehicle_msgs::msg::SteeringReport;
@@ -75,22 +78,25 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
//!< @brief topic publisher for low level vehicle command
rclcpp::Publisher::SharedPtr pub_actuation_cmd_;
+ rclcpp::Publisher::SharedPtr pub_steering_status_;
//!< @brief subscriber for vehicle command
rclcpp::Subscription::SharedPtr sub_control_cmd_;
+ rclcpp::Subscription::SharedPtr sub_actuation_status_;
+ rclcpp::Subscription::SharedPtr sub_steering_;
// polling subscribers
autoware::universe_utils::InterProcessPollingSubscriber sub_odometry_{
this, "~/input/odometry"};
- autoware::universe_utils::InterProcessPollingSubscriber sub_steering_{
- this, "~/input/steering"};
rclcpp::TimerBase::SharedPtr timer_;
std::unique_ptr current_twist_ptr_; // [m/s]
std::unique_ptr current_steer_ptr_;
+ ActuationStatusStamped::ConstSharedPtr actuation_status_ptr_;
Control::ConstSharedPtr control_cmd_ptr_;
AccelMap accel_map_;
BrakeMap brake_map_;
SteerMap steer_map_;
+ VGR vgr_;
// TODO(tanaka): consider accel/brake pid too
PIDController steer_pid_;
bool ff_map_initialized_;
@@ -102,16 +108,24 @@ class RawVehicleCommandConverterNode : public rclcpp::Node
bool use_steer_ff_;
bool use_steer_fb_;
bool is_debugging_;
- bool convert_accel_cmd_; //!< @brief use accel or not
- bool convert_brake_cmd_; //!< @brief use brake or not
- bool convert_steer_cmd_; //!< @brief use steer or not
+ bool convert_accel_cmd_; //!< @brief use accel or not
+ bool convert_brake_cmd_; //!< @brief use brake or not
+ std::optional convert_steer_cmd_method_{std::nullopt}; //!< @brief method to convert
+ bool need_to_subscribe_actuation_status_{false};
rclcpp::Time prev_time_steer_calculation_{0, 0, RCL_ROS_TIME};
+ // Whether to subscribe to actuation_status and calculate and publish steering_status
+ // For example, receive the steering wheel angle and calculate the steering wheel angle based on
+ // the gear ratio. If false, the vehicle interface must publish steering_status.
+ bool convert_actuation_to_steering_status_{false}; // !< @brief use actuation_status or not
+
double calculateAccelMap(
const double current_velocity, const double desired_acc, bool & accel_cmd_is_zero);
double calculateBrakeMap(const double current_velocity, const double desired_acc);
- double calculateSteer(const double vel, const double steering, const double steer_rate);
+ double calculateSteerFromMap(const double vel, const double steering, const double steer_rate);
void onControlCmd(const Control::ConstSharedPtr msg);
+ void onSteering(const Steering::ConstSharedPtr msg);
+ void onActuationStatus(const ActuationStatusStamped::ConstSharedPtr msg);
void publishActuationCmd();
// for debugging
rclcpp::Publisher::SharedPtr debug_pub_steer_pid_;
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vgr.hpp b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vgr.hpp
new file mode 100644
index 0000000000000..3b795c4d51036
--- /dev/null
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/include/autoware_raw_vehicle_cmd_converter/vgr.hpp
@@ -0,0 +1,39 @@
+// Copyright 2024 Tier IV, Inc. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VGR_HPP_
+#define AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VGR_HPP_
+
+namespace autoware::raw_vehicle_cmd_converter
+{
+class VGR
+{
+public:
+ VGR() = default;
+ VGR(const double vgr_coef_a, const double vgr_coef_b, const double vgr_coef_c)
+ : vgr_coef_a_(vgr_coef_a), vgr_coef_b_(vgr_coef_b), vgr_coef_c_(vgr_coef_c)
+ {
+ }
+ void setCoefficients(double a, double b, double c);
+ double calculateVariableGearRatio(double vel, double steer_wheel) const;
+ double calculateSteeringTireState(double vel, double steer_wheel) const;
+
+private:
+ double vgr_coef_a_{0.0};
+ double vgr_coef_b_{0.0};
+ double vgr_coef_c_{0.0};
+};
+} // namespace autoware::raw_vehicle_cmd_converter
+
+#endif // AUTOWARE_RAW_VEHICLE_CMD_CONVERTER__VGR_HPP_
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
index 735d51e80d5d4..441d924a0e6c3 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/launch/raw_vehicle_converter.launch.xml
@@ -3,7 +3,9 @@
+
+
@@ -12,6 +14,8 @@
+
+
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
index 1903f8252d656..30642663a39f5 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/schema/raw_vehicle_cmd_converter.schema.json
@@ -154,6 +154,32 @@
"min_d",
"invalid_integration_decay"
]
+ },
+ "convert_steer_cmd_method": {
+ "type": "string",
+ "description": "method for converting steer command",
+ "default": "vgr",
+ "enum": ["vgr", "steer_map"]
+ },
+ "vgr_coef_a": {
+ "type": "number",
+ "default": "15.713",
+ "description": "coefficient a for variable gear ratio"
+ },
+ "vgr_coef_b": {
+ "type": "number",
+ "default": "0.053",
+ "description": "coefficient b for variable gear ratio"
+ },
+ "vgr_coef_c": {
+ "type": "number",
+ "default": "0.042",
+ "description": "coefficient c for variable gear ratio"
+ },
+ "convert_actuation_to_steering_status": {
+ "type": "boolean",
+ "default": "true",
+ "description": "convert actuation to steering status or not. Whether to subscribe to actuation_status and calculate and publish steering_status For example, receive the steering wheel angle and calculate the steering wheel angle based on the gear ratio. If false, the vehicle interface must publish steering_status."
}
},
"required": [
@@ -169,7 +195,12 @@
"max_throttle",
"max_brake",
"max_steer",
- "steer_pid"
+ "steer_pid",
+ "convert_steer_cmd_method",
+ "vgr_coef_a",
+ "vgr_coef_b",
+ "vgr_coef_c",
+ "convert_actuation_to_steering_status"
]
}
},
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_variable_gear_ratio.py b/vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_variable_gear_ratio.py
new file mode 100755
index 0000000000000..f7f8cd6cb3395
--- /dev/null
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/scripts/plot_variable_gear_ratio.py
@@ -0,0 +1,107 @@
+#!/usr/bin/env python3
+
+# Copyright 2024 Tier IV, Inc. All rights reserved.
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+import argparse
+
+import matplotlib.pyplot as plt
+import numpy as np
+
+
+def calculate_variable_gear_ratio(vel, steer_wheel, a, b, c):
+ return max(1e-5, a + b * vel * vel - c * abs(steer_wheel))
+
+
+def plot_vgr_vs_steer_wheel(ax, velocity, a, b, c):
+ steer_wheel_values = np.linspace(-10.0, 10.0, 100)
+ vgr_values = [
+ calculate_variable_gear_ratio(velocity, steer_wheel, a, b, c)
+ for steer_wheel in steer_wheel_values
+ ]
+
+ ax.plot(
+ steer_wheel_values,
+ vgr_values,
+ linewidth=2,
+ )
+ ax.set_xlabel("Steer Wheel [rad]", fontsize=14)
+ ax.set_ylabel("Variable Gear Ratio", fontsize=14)
+ ax.set_title(
+ f"VGR vs Steer Wheel\n(Velocity = {velocity} m/s, a = {a}, b = {b}, c = {c})",
+ fontsize=16,
+ fontweight="bold",
+ )
+ ax.grid(True, linestyle="--", alpha=0.7)
+ ax.tick_params(axis="both", which="major", labelsize=12)
+
+
+def plot_vgr_vs_velocity(ax, steer_wheel, a, b, c):
+ velocity_values = np.linspace(0, 16.66, 100)
+ vgr_values = [
+ calculate_variable_gear_ratio(velocity, steer_wheel, a, b, c)
+ for velocity in velocity_values
+ ]
+
+ ax.plot(velocity_values, vgr_values, linewidth=2)
+ ax.set_xlabel("Velocity [m/s]", fontsize=14)
+ ax.set_ylabel("Variable Gear Ratio", fontsize=14)
+ ax.set_title(
+ f"VGR vs Velocity\n(Steer Wheel = {steer_wheel} rad, a = {a}, b = {b}, c = {c})",
+ fontsize=16,
+ fontweight="bold",
+ )
+ ax.grid(True, linestyle="--", alpha=0.7)
+ ax.tick_params(axis="both", which="major", labelsize=12)
+
+
+def main():
+ parser = argparse.ArgumentParser(
+ description="Plot Variable Gear Ratio (VGR) based on velocity and steer wheel angle."
+ )
+ parser.add_argument("--vgr_coef_a", type=float, default=15.713, help="Coefficient a for VGR")
+ parser.add_argument("--vgr_coef_b", type=float, default=0.053, help="Coefficient b for VGR")
+ parser.add_argument("--vgr_coef_c", type=float, default=0.042, help="Coefficient c for VGR")
+ parser.add_argument(
+ "--velocity",
+ type=float,
+ default=8.33,
+ help="Fixed velocity value for plotting VGR vs Steer Wheel",
+ )
+ parser.add_argument(
+ "--steer_wheel",
+ type=float,
+ default=0.0,
+ help="Fixed steer wheel value for plotting VGR vs Velocity",
+ )
+
+ args = parser.parse_args()
+
+ plt.style.use("seaborn-whitegrid")
+
+ fig, axs = plt.subplots(1, 2, figsize=(16, 8))
+
+ plot_vgr_vs_steer_wheel(
+ axs[0], args.velocity, args.vgr_coef_a, args.vgr_coef_b, args.vgr_coef_c
+ )
+ plot_vgr_vs_velocity(
+ axs[1], args.steer_wheel, args.vgr_coef_a, args.vgr_coef_b, args.vgr_coef_c
+ )
+
+ plt.tight_layout()
+ plt.show()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
index c4d7ea11bbcf3..6fb8f4dff44f6 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp
@@ -29,10 +29,8 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
/* parameters for accel/brake map */
const auto csv_path_accel_map = declare_parameter("csv_path_accel_map");
const auto csv_path_brake_map = declare_parameter("csv_path_brake_map");
- const auto csv_path_steer_map = declare_parameter("csv_path_steer_map");
convert_accel_cmd_ = declare_parameter("convert_accel_cmd");
convert_brake_cmd_ = declare_parameter("convert_brake_cmd");
- convert_steer_cmd_ = declare_parameter("convert_steer_cmd");
max_accel_cmd_ = declare_parameter("max_throttle");
max_brake_cmd_ = declare_parameter("max_brake");
max_steer_cmd_ = declare_parameter("max_steer");
@@ -51,33 +49,68 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
throw std::invalid_argument("Brake map is invalid.");
}
}
- if (convert_steer_cmd_) {
- if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map, true)) {
- throw std::invalid_argument("Steer map is invalid.");
+ if (declare_parameter("convert_steer_cmd")) {
+ convert_steer_cmd_method_ = declare_parameter("convert_steer_cmd_method", "vgr");
+ if (convert_steer_cmd_method_.value() == "vgr") {
+ const double a = declare_parameter("vgr_coef_a");
+ const double b = declare_parameter("vgr_coef_b");
+ const double c = declare_parameter("vgr_coef_c");
+ vgr_.setCoefficients(a, b, c);
+ } else if (convert_steer_cmd_method_.value() == "steer_map") {
+ const auto csv_path_steer_map = declare_parameter("csv_path_steer_map");
+ if (!steer_map_.readSteerMapFromCSV(csv_path_steer_map, true)) {
+ throw std::invalid_argument("Steer map is invalid.");
+ }
+ const auto kp_steer{declare_parameter("steer_pid.kp")};
+ const auto ki_steer{declare_parameter("steer_pid.ki")};
+ const auto kd_steer{declare_parameter("steer_pid.kd")};
+ const auto max_ret_steer{declare_parameter("steer_pid.max")};
+ const auto min_ret_steer{declare_parameter("steer_pid.min")};
+ const auto max_ret_p_steer{declare_parameter("steer_pid.max_p")};
+ const auto min_ret_p_steer{declare_parameter("steer_pid.min_p")};
+ const auto max_ret_i_steer{declare_parameter("steer_pid.max_i")};
+ const auto min_ret_i_steer{declare_parameter("steer_pid.min_i")};
+ const auto max_ret_d_steer{declare_parameter("steer_pid.max_d")};
+ const auto min_ret_d_steer{declare_parameter("steer_pid.min_d")};
+ const auto invalid_integration_decay{
+ declare_parameter("steer_pid.invalid_integration_decay")};
+ steer_pid_.setDecay(invalid_integration_decay);
+ steer_pid_.setGains(kp_steer, ki_steer, kd_steer);
+ steer_pid_.setLimits(
+ max_ret_steer, min_ret_steer, max_ret_p_steer, min_ret_p_steer, max_ret_i_steer,
+ min_ret_i_steer, max_ret_d_steer, min_ret_d_steer);
+ steer_pid_.setInitialized();
+ } else {
+ throw std::invalid_argument("Invalid steer conversion method.");
}
- const auto kp_steer{declare_parameter("steer_pid.kp")};
- const auto ki_steer{declare_parameter("steer_pid.ki")};
- const auto kd_steer{declare_parameter("steer_pid.kd")};
- const auto max_ret_steer{declare_parameter("steer_pid.max")};
- const auto min_ret_steer{declare_parameter("steer_pid.min")};
- const auto max_ret_p_steer{declare_parameter("steer_pid.max_p")};
- const auto min_ret_p_steer{declare_parameter("steer_pid.min_p")};
- const auto max_ret_i_steer{declare_parameter("steer_pid.max_i")};
- const auto min_ret_i_steer{declare_parameter("steer_pid.min_i")};
- const auto max_ret_d_steer{declare_parameter("steer_pid.max_d")};
- const auto min_ret_d_steer{declare_parameter("steer_pid.min_d")};
- const auto invalid_integration_decay{
- declare_parameter("steer_pid.invalid_integration_decay")};
- steer_pid_.setDecay(invalid_integration_decay);
- steer_pid_.setGains(kp_steer, ki_steer, kd_steer);
- steer_pid_.setLimits(
- max_ret_steer, min_ret_steer, max_ret_p_steer, min_ret_p_steer, max_ret_i_steer,
- min_ret_i_steer, max_ret_d_steer, min_ret_d_steer);
- steer_pid_.setInitialized();
}
- pub_actuation_cmd_ = create_publisher("~/output/actuation_cmd", 1);
+
+ // NOTE: The steering status can be published from the vehicle side or converted in this node.
+ convert_actuation_to_steering_status_ =
+ declare_parameter("convert_actuation_to_steering_status");
+ if (convert_actuation_to_steering_status_) {
+ pub_steering_status_ = create_publisher("~/output/steering_status", 1);
+ } else {
+ // NOTE: Polling subscriber requires specifying the topic name at declaration,
+ // so use a normal callback subscriber.
+ sub_steering_ = create_subscription(
+ "~/input/steering", 1, std::bind(&RawVehicleCommandConverterNode::onSteering, this, _1));
+ }
+
+ // NOTE: some vehicles do not publish actuation status. To handle this, subscribe only when the
+ // option is specified.
+ need_to_subscribe_actuation_status_ =
+ convert_actuation_to_steering_status_ || convert_steer_cmd_method_.value() == "vgr";
+ if (need_to_subscribe_actuation_status_) {
+ sub_actuation_status_ = create_subscription(
+ "~/input/actuation_status", 1,
+ std::bind(&RawVehicleCommandConverterNode::onActuationStatus, this, _1));
+ }
+
sub_control_cmd_ = create_subscription(
"~/input/control_cmd", 1, std::bind(&RawVehicleCommandConverterNode::onControlCmd, this, _1));
+
+ pub_actuation_cmd_ = create_publisher("~/output/actuation_cmd", 1);
debug_pub_steer_pid_ = create_publisher(
"/vehicle/raw_vehicle_cmd_converter/debug/steer_pid", 1);
@@ -86,13 +119,21 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode(
void RawVehicleCommandConverterNode::publishActuationCmd()
{
- if (!current_twist_ptr_ || !control_cmd_ptr_ || !current_steer_ptr_) {
+ if (!current_twist_ptr_ || !control_cmd_ptr_ || !current_steer_ptr_ || !actuation_status_ptr_) {
RCLCPP_WARN_EXPRESSION(
get_logger(), is_debugging_, "some pointers are null: %s, %s, %s",
!current_twist_ptr_ ? "twist" : "", !control_cmd_ptr_ ? "cmd" : "",
!current_steer_ptr_ ? "steer" : "");
return;
}
+
+ if (need_to_subscribe_actuation_status_) {
+ if (!actuation_status_ptr_) {
+ RCLCPP_WARN_EXPRESSION(get_logger(), is_debugging_, "actuation status is null");
+ return;
+ }
+ }
+
double desired_accel_cmd = 0.0;
double desired_brake_cmd = 0.0;
double desired_steer_cmd = 0.0;
@@ -116,11 +157,18 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
// if conversion is disabled use negative acceleration as brake cmd
desired_brake_cmd = -acc;
}
- if (convert_steer_cmd_) {
- desired_steer_cmd = calculateSteer(vel, steer, steer_rate);
- } else {
+ if (!convert_steer_cmd_method_.has_value()) {
// if conversion is disabled use steering angle as steer cmd
desired_steer_cmd = steer;
+ } else if (convert_steer_cmd_method_.value() == "vgr") {
+ // NOTE: When using variable gear ratio,
+ // the actuation cmd is the steering wheel angle,
+ // and the actuation_status is also the steering wheel angle.
+ const double current_steer_wheel = actuation_status_ptr_->status.steer_status;
+ const double adaptive_gear_ratio = vgr_.calculateVariableGearRatio(vel, current_steer_wheel);
+ desired_steer_cmd = steer * adaptive_gear_ratio;
+ } else if (convert_steer_cmd_method_.value() == "steer_map") {
+ desired_steer_cmd = calculateSteerFromMap(vel, steer, steer_rate);
}
actuation_cmd.header.frame_id = "base_link";
actuation_cmd.header.stamp = control_cmd_ptr_->stamp;
@@ -130,7 +178,7 @@ void RawVehicleCommandConverterNode::publishActuationCmd()
pub_actuation_cmd_->publish(actuation_cmd);
}
-double RawVehicleCommandConverterNode::calculateSteer(
+double RawVehicleCommandConverterNode::calculateSteerFromMap(
const double vel, const double steering, const double steer_rate)
{
double steering_output = 0;
@@ -203,10 +251,6 @@ double RawVehicleCommandConverterNode::calculateBrakeMap(
void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr msg)
{
const auto odometry_msg = sub_odometry_.takeData();
- const auto steering_msg = sub_steering_.takeData();
- if (steering_msg) {
- current_steer_ptr_ = std::make_unique(steering_msg->steering_tire_angle);
- }
if (odometry_msg) {
current_twist_ptr_ = std::make_unique();
current_twist_ptr_->header = odometry_msg->header;
@@ -215,6 +259,41 @@ void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr
control_cmd_ptr_ = msg;
publishActuationCmd();
}
+
+void RawVehicleCommandConverterNode::onSteering(const Steering::ConstSharedPtr msg)
+{
+ current_steer_ptr_ = std::make_unique(msg->steering_tire_angle);
+}
+
+void RawVehicleCommandConverterNode::onActuationStatus(
+ const ActuationStatusStamped::ConstSharedPtr msg)
+{
+ actuation_status_ptr_ = msg;
+
+ if (!convert_actuation_to_steering_status_) {
+ return;
+ }
+
+ // calculate steering status from actuation status
+ const auto odometry_msg = sub_odometry_.takeData();
+ if (odometry_msg) {
+ if (convert_steer_cmd_method_.value() == "vgr") {
+ current_twist_ptr_ = std::make_unique();
+ current_twist_ptr_->header = odometry_msg->header;
+ current_twist_ptr_->twist = odometry_msg->twist.twist;
+ current_steer_ptr_ = std::make_unique(vgr_.calculateSteeringTireState(
+ current_twist_ptr_->twist.linear.x, actuation_status_ptr_->status.steer_status));
+ Steering steering_msg{};
+ steering_msg.steering_tire_angle = *current_steer_ptr_;
+ pub_steering_status_->publish(steering_msg);
+ } else if (convert_steer_cmd_method_.value() == "steer_map") {
+ throw std::domain_error(
+ "Steer map conversion is not supported for actuation status. Please "
+ "use vgr conversion method or set convert_actuation_to_steering to "
+ "false.");
+ }
+ }
+}
} // namespace autoware::raw_vehicle_cmd_converter
#include
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/vgr.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/vgr.cpp
new file mode 100644
index 0000000000000..13463d1678ac8
--- /dev/null
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/vgr.cpp
@@ -0,0 +1,41 @@
+// Copyright 2024 Tier IV, Inc. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "autoware_raw_vehicle_cmd_converter/vgr.hpp"
+
+#include
+#include
+
+namespace autoware::raw_vehicle_cmd_converter
+{
+
+void VGR::setCoefficients(const double a, const double b, const double c)
+{
+ vgr_coef_a_ = a;
+ vgr_coef_b_ = b;
+ vgr_coef_c_ = c;
+}
+
+double VGR::calculateVariableGearRatio(const double vel, const double steer_wheel) const
+{
+ return std::max(
+ 1e-5, vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs(steer_wheel));
+}
+
+double VGR::calculateSteeringTireState(const double vel, const double steer_wheel) const
+{
+ const double adaptive_gear_ratio = calculateVariableGearRatio(vel, steer_wheel);
+ return steer_wheel / adaptive_gear_ratio;
+}
+} // namespace autoware::raw_vehicle_cmd_converter
diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
index 746f872789b07..59ab3a880fabd 100644
--- a/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
+++ b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp
@@ -17,6 +17,7 @@
#include "autoware_raw_vehicle_cmd_converter/brake_map.hpp"
#include "autoware_raw_vehicle_cmd_converter/pid.hpp"
#include "autoware_raw_vehicle_cmd_converter/steer_map.hpp"
+#include "autoware_raw_vehicle_cmd_converter/vgr.hpp"
#include "gtest/gtest.h"
#include
@@ -52,6 +53,7 @@ using autoware::raw_vehicle_cmd_converter::AccelMap;
using autoware::raw_vehicle_cmd_converter::BrakeMap;
using autoware::raw_vehicle_cmd_converter::PIDController;
using autoware::raw_vehicle_cmd_converter::SteerMap;
+using autoware::raw_vehicle_cmd_converter::VGR;
double epsilon = 1e-4;
// may throw PackageNotFoundError exception for invalid package
const auto map_path =
@@ -297,3 +299,49 @@ TEST(PIDTests, calculateFB)
EXPECT_NEAR(pid_contributions.at(1), 0.21825, epsilon);
EXPECT_NEAR(pid_contributions.at(2), -0.15, epsilon);
}
+
+TEST(VGRTests, roundTrip)
+{
+ VGR vgr;
+ vgr.setCoefficients(15.713, 0.053, 0.042);
+ double vel = 5.0;
+ double steer_wheel = 0.1;
+ double gear_ratio = vgr.calculateVariableGearRatio(vel, steer_wheel);
+ double steer = vgr.calculateSteeringTireState(vel, steer_wheel);
+ double steer_wheel2 = steer * gear_ratio;
+ EXPECT_NEAR(steer_wheel, steer_wheel2, epsilon);
+}
+
+TEST(VGRTests, boundaryValues)
+{
+ VGR vgr;
+ vgr.setCoefficients(15.713, 0.053, 0.042);
+
+ const double vel = 0.0;
+ const double steer_wheel = 0.0;
+ const double gear_ratio = vgr.calculateVariableGearRatio(vel, steer_wheel);
+ EXPECT_NEAR(gear_ratio, 15.713, epsilon);
+
+ const double steer_wheel_small = 1e-5;
+ const double steer = vgr.calculateSteeringTireState(vel, steer_wheel_small);
+ const double steer_wheel2 = steer * gear_ratio;
+ EXPECT_NEAR(steer_wheel, steer_wheel2, epsilon);
+}
+
+TEST(VGRTests, zeroCoefficients)
+{
+ VGR vgr;
+ vgr.setCoefficients(0.0, 0.0, 0.0);
+
+ const double vel = 10.0;
+ const double steer_wheel = 0.5;
+
+ // Gear ratio should return the minimum value since all coefficients are zero
+ const double gear_ratio = vgr.calculateVariableGearRatio(vel, steer_wheel);
+ EXPECT_EQ(gear_ratio, 1e-5);
+
+ // Steering tire state calculation is also performed with the minimum gear ratio
+ const double steer = vgr.calculateSteeringTireState(vel, steer_wheel);
+ const double steer_wheel2 = steer * gear_ratio;
+ EXPECT_NEAR(steer_wheel, steer_wheel2, epsilon);
+}
From 6988233252205bc06d70494e3e3498f4da38dbde Mon Sep 17 00:00:00 2001
From: Kosuke Takeuchi
Date: Thu, 22 Aug 2024 14:00:09 +0900
Subject: [PATCH 006/169] feat(simple_planning_simulator): add VGR sim model
(#8415)
* feat(simple_planning_simulator): add VGR sim model
Signed-off-by: kosuke55
* Update simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp
* move to interface
Signed-off-by: kosuke55
* add const
Signed-off-by: kosuke55
---------
Signed-off-by: kosuke55
---
simulator/simple_planning_simulator/README.md | 31 +-
.../simple_planning_simulator_core.hpp | 9 +
.../vehicle_model/sim_model_actuation_cmd.hpp | 137 +++-
.../vehicle_model/sim_model_interface.hpp | 15 +
.../simple_planning_simulator.launch.py | 3 +-
.../media/vgr_sim.drawio.svg | 691 ++++++++++++++++++
.../simple_planning_simulator_core.cpp | 60 +-
.../vehicle_model/sim_model_actuation_cmd.cpp | 167 ++++-
.../test/test_simple_planning_simulator.cpp | 53 +-
9 files changed, 1127 insertions(+), 39 deletions(-)
create mode 100644 simulator/simple_planning_simulator/media/vgr_sim.drawio.svg
diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md
index d44264035ecc4..1d91d5e6149b4 100644
--- a/simulator/simple_planning_simulator/README.md
+++ b/simulator/simple_planning_simulator/README.md
@@ -127,17 +127,30 @@ default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 1
The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched.
+`convert_steer_cmd_method` has two options: "vgr" and "steer_map". If you choose "vgr" (variable gear ratio), it is assumed that the steering wheel angle is sent as the actuation command, and the value is converted to the steering tire angle to move the model. If you choose "steer_map", it is assumed that an arbitrary value is sent as the actuation command, and the value is converted to the steering tire rate to move the model. An arbitrary value is like EPS (Electric Power Steering) Voltage . `enable_pub_steer` determines whether to publish the steering tire angle. If false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter).
+
+![vgr_sim](./media/vgr_sim.drawio.svg)
+
+```yaml
+
+```
+
The parameters used in the ACTUATION_CMD are as follows.
-| Name | Type | Description | unit |
-| :------------------ | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- |
-| accel_time_delay | double | dead time for the acceleration input | [s] |
-| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] |
-| brake_time_delay | double | dead time for the brake input | [s] |
-| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] |
-| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] |
-| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] |
-| convert_steer_cmd | bool | If true, it is assumed that the command is received converted to a steer actuation value, and it is converted back to steer rate value inside the simulator. | [-] |
+| Name | Type | Description | unit |
+| :----------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- |
+| accel_time_delay | double | dead time for the acceleration input | [s] |
+| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] |
+| brake_time_delay | double | dead time for the brake input | [s] |
+| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] |
+| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] |
+| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] |
+| convert_steer_cmd | bool | If true, it is assumed that the command is received converted to a steer actuation value, and it is converted back to steer rate value inside the simulator. | [-] |
+| convert_steer_cmd_method | bool | method to convert steer command. You can choose from "vgr" and "steer_map". | [-] |
+| vgr_coef_a | double | the value of the coefficient a of the variable gear ratio | [-] |
+| vgr_coef_b | double | the value of the coefficient b of the variable gear ratio | [-] |
+| vgr_coef_c | double | the value of the coefficient c of the variable gear ratio | [-] |
+| enable_pub_steer | bool | whether to publish the steering tire angle. if false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter) | [-] |
diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp
index 547689dc847a0..76fdf5bdda6c9 100644
--- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp
+++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp
@@ -45,6 +45,7 @@
#include "sensor_msgs/msg/imu.hpp"
#include "tier4_external_api_msgs/srv/initialize_pose.hpp"
#include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp"
+#include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp"
#include
#include
@@ -86,6 +87,7 @@ using nav_msgs::msg::Odometry;
using sensor_msgs::msg::Imu;
using tier4_external_api_msgs::srv::InitializePose;
using tier4_vehicle_msgs::msg::ActuationCommandStamped;
+using tier4_vehicle_msgs::msg::ActuationStatusStamped;
class DeltaTime
{
@@ -138,6 +140,7 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
rclcpp::Publisher::SharedPtr pub_hazard_lights_report_;
rclcpp::Publisher::SharedPtr pub_tf_;
rclcpp::Publisher::SharedPtr pub_current_pose_;
+ rclcpp::Publisher::SharedPtr pub_actuation_status_;
rclcpp::Subscription::SharedPtr sub_gear_cmd_;
rclcpp::Subscription::SharedPtr sub_manual_gear_cmd_;
@@ -189,6 +192,10 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
ControlModeReport current_control_mode_{};
bool enable_road_slope_simulation_ = true;
+ // if false, it is expected to be converted and published from actuation_status in other nodes
+ // (e.g. raw_vehicle_cmd_converter)
+ bool enable_pub_steer_ = true; //!< @brief flag to publish steering report.
+
/* frame_id */
std::string simulated_frame_id_ = ""; //!< @brief simulated vehicle frame id
std::string origin_frame_id_ = ""; //!< @brief map frame_id
@@ -388,6 +395,8 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node
*/
void publish_hazard_lights_report();
+ void publish_actuation_status();
+
/**
* @brief publish tf
* @param [in] state The kinematic state to publish as a TF
diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp
index 1385a509b8dca..5615f5c118165 100644
--- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp
+++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp
@@ -23,13 +23,22 @@
#include
#include
+#include
#include
#include
#include
/**
* @class ActuationMap
- * @brief class to convert actuation command
+ * @brief class to convert from actuation command to control command
+ *
+ * ------- state ------->
+ * |
+ * |
+ * actuation control
+ * |
+ * |
+ * V
*/
class ActuationMap
{
@@ -43,12 +52,48 @@ class ActuationMap
bool readActuationMapFromCSV(const std::string & csv_path, const bool validation = false);
double getControlCommand(const double actuation, const double state) const;
-private:
+protected:
std::vector state_index_; // e.g. velocity, steering
std::vector actuation_index_;
std::vector> actuation_map_;
};
+/**
+ * @class AccelMap
+ * @brief class to get throttle from acceleration
+ *
+ * ------- vel ------>
+ * |
+ * |
+ * throttle acc
+ * |
+ * |
+ * V
+ */
+class AccelMap : public ActuationMap
+{
+public:
+ std::optional getThrottle(const double acc, const double vel) const;
+};
+
+/**
+ * @class BrakeMap
+ * @brief class to get brake from acceleration
+ *
+ * ------- vel ------>
+ * |
+ * |
+ * brake acc
+ * |
+ * |
+ * V
+ */
+class BrakeMap : public ActuationMap
+{
+public:
+ double getBrake(const double acc, const double vel) const;
+};
+
/**
* @class SimModelActuationCmd
* @brief class to handle vehicle model with actuation command
@@ -56,8 +101,42 @@ class ActuationMap
class SimModelActuationCmd : public SimModelInterface
{
public:
+ enum class ActuationSimType { VGR, STEER_MAP };
+
/**
- * @brief constructor
+ * @brief constructor (adaptive gear ratio conversion model)
+ * @param [in] vx_lim velocity limit [m/s]
+ * @param [in] steer_lim steering limit [rad]
+ * @param [in] vx_rate_lim acceleration limit [m/ss]
+ * @param [in] steer_rate_lim steering angular velocity limit [rad/ss]
+ * @param [in] wheelbase vehicle wheelbase length [m]
+ * @param [in] dt delta time information to set input buffer for delay
+ * @param [in] accel_delay time delay for accel command [s]
+ * @param [in] acc_time_constant time constant for 1D model of accel dynamics
+ * @param [in] brake_delay time delay for brake command [s]
+ * @param [in] brake_time_constant time constant for 1D model of brake dynamics
+ * @param [in] steer_delay time delay for steering command [s]
+ * @param [in] steer_time_constant time constant for 1D model of steering dynamics
+ * @param [in] steer_bias steering bias [rad]
+ * @param [in] convert_accel_cmd flag to convert accel command
+ * @param [in] convert_brake_cmd flag to convert brake command
+ * @param [in] convert_steer_cmd flag to convert steer command
+ * @param [in] accel_map_path path to csv file for accel conversion map
+ * @param [in] brake_map_path path to csv file for brake conversion map
+ * @param [in] vgr_coef_a coefficient for variable gear ratio
+ * @param [in] vgr_coef_b coefficient for variable gear ratio
+ * @param [in] vgr_coef_c coefficient for variable gear ratio
+ */
+ SimModelActuationCmd(
+ double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase,
+ double dt, double accel_delay, double accel_time_constant, double brake_delay,
+ double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias,
+ bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd,
+ std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b,
+ double vgr_coef_c);
+
+ /**
+ * @brief constructor (steer map conversion model)
* @param [in] vx_lim velocity limit [m/s]
* @param [in] steer_lim steering limit [rad]
* @param [in] vx_rate_lim acceleration limit [m/ss]
@@ -90,13 +169,15 @@ class SimModelActuationCmd : public SimModelInterface
*/
~SimModelActuationCmd() = default;
- ActuationMap accel_map_;
- ActuationMap brake_map_;
- ActuationMap steer_map_;
+ /*
+ * @brief get actuation status
+ */
+ std::optional getActuationStatus() const override;
- bool convert_accel_cmd_;
- bool convert_brake_cmd_;
- bool convert_steer_cmd_;
+ /**
+ * @brief is publish actuation status enabled
+ */
+ bool shouldPublishActuationStatus() const override { return true; }
private:
const double MIN_TIME_CONSTANT; //!< @brief minimum time constant
@@ -133,7 +214,23 @@ class SimModelActuationCmd : public SimModelInterface
const double steer_delay_; //!< @brief time delay for steering command [s]
const double steer_time_constant_; //!< @brief time constant for steering dynamics
const double steer_bias_; //!< @brief steering angle bias [rad]
- const std::string path_; //!< @brief conversion map path
+
+ bool convert_accel_cmd_;
+ bool convert_brake_cmd_;
+ bool convert_steer_cmd_;
+
+ AccelMap accel_map_;
+ BrakeMap brake_map_;
+ ActuationMap steer_map_;
+
+ // steer map conversion model
+
+ // adaptive gear ratio conversion model
+ double vgr_coef_a_;
+ double vgr_coef_b_;
+ double vgr_coef_c_;
+
+ ActuationSimType actuation_sim_type_{ActuationSimType::VGR};
/**
* @brief set queue buffer for input command
@@ -204,6 +301,26 @@ class SimModelActuationCmd : public SimModelInterface
void updateStateWithGear(
Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear,
const double dt);
+
+ /**
+ * @brief calculate steering tire command
+ * @param [in] vel current velocity [m/s]
+ * @param [in] steer current steering angle [rad]
+ * @param [in] steer_wheel_des desired steering wheel angle [rad]
+ * @return steering tire command
+ */
+ double calculateSteeringTireCommand(
+ const double vel, const double steer, const double steer_wheel_des) const;
+
+ double calculateSteeringWheelState(const double target_tire_angle, const double vel) const;
+
+ /**
+ * @brief calculate variable gear ratio
+ * @param [in] vel current velocity [m/s]
+ * @param [in] steer_wheel current steering wheel angle [rad]
+ * @return variable gear ratio
+ */
+ double calculateVariableGearRatio(const double vel, const double steer_wheel) const;
};
#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_
diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp
index 1274a1ec28a07..f8d682a6e851c 100644
--- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp
+++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp
@@ -18,6 +18,9 @@
#include
#include "autoware_vehicle_msgs/msg/gear_command.hpp"
+#include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp"
+
+#include
/**
* @class SimModelInterface
@@ -26,6 +29,8 @@
class SimModelInterface
{
protected:
+ using ActuationStatusStamped = tier4_vehicle_msgs::msg::ActuationStatusStamped;
+
const int dim_x_; //!< @brief dimension of state x
const int dim_u_; //!< @brief dimension of input u
Eigen::VectorXd state_; //!< @brief vehicle state vector
@@ -152,6 +157,16 @@ class SimModelInterface
*/
inline int getDimU() { return dim_u_; }
+ /**
+ * @brief is publish actuation status enabled
+ */
+ virtual bool shouldPublishActuationStatus() const { return false; }
+
+ /*
+ * @brief get actuation status
+ */
+ virtual std::optional getActuationStatus() const { return std::nullopt; }
+
/**
* @brief calculate derivative of states with vehicle model
* @param [in] state current model state
diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py
index e6a35bd420bf3..9b31926a53d57 100644
--- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py
+++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py
@@ -62,6 +62,7 @@ def launch_setup(context, *args, **kwargs):
("output/turn_indicators_report", "/vehicle/status/turn_indicators_status"),
("output/hazard_lights_report", "/vehicle/status/hazard_lights_status"),
("output/control_mode_report", "/vehicle/status/control_mode"),
+ ("output/actuation_status", "/vehicle/status/actuation_status"),
]
# Additional remappings
@@ -110,8 +111,6 @@ def launch_setup(context, *args, **kwargs):
== "ACTUATION_CMD"
)
- # launch_vehicle_cmd_converter = False # tmp
-
# 1) Launch only simple_planning_simulator_node
if not launch_vehicle_cmd_converter:
return [simple_planning_simulator_node]
diff --git a/simulator/simple_planning_simulator/media/vgr_sim.drawio.svg b/simulator/simple_planning_simulator/media/vgr_sim.drawio.svg
new file mode 100644
index 0000000000000..dea871dd73797
--- /dev/null
+++ b/simulator/simple_planning_simulator/media/vgr_sim.drawio.svg
@@ -0,0 +1,691 @@
+
+
+
+
diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp
index 4252ace6c1920..96cfa1587e646 100644
--- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp
+++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp
@@ -103,6 +103,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt
add_measurement_noise_ = declare_parameter("add_measurement_noise", false);
simulate_motion_ = declare_parameter("initial_engage_state");
enable_road_slope_simulation_ = declare_parameter("enable_road_slope_simulation", false);
+ enable_pub_steer_ = declare_parameter("enable_pub_steer", true);
using rclcpp::QoS;
using std::placeholders::_1;
@@ -168,10 +169,14 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt
pub_current_pose_ = create_publisher("output/pose", QoS{1});
pub_velocity_ = create_publisher("output/twist", QoS{1});
pub_odom_ = create_publisher("output/odometry", QoS{1});
- pub_steer_ = create_publisher("output/steering", QoS{1});
pub_acc_ = create_publisher("output/acceleration", QoS{1});
pub_imu_ = create_publisher("output/imu", QoS{1});
pub_tf_ = create_publisher("/tf", QoS{1});
+ pub_actuation_status_ =
+ create_publisher("output/actuation_status", QoS{1});
+ if (enable_pub_steer_) {
+ pub_steer_ = create_publisher("output/steering", QoS{1});
+ }
/* set param callback */
set_param_res_ = this->add_on_set_parameters_callback(
@@ -323,13 +328,33 @@ void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehic
// actuation conversion map
const std::string accel_map_path = declare_parameter("accel_map_path");
const std::string brake_map_path = declare_parameter("brake_map_path");
- const std::string steer_map_path = declare_parameter("steer_map_path");
- vehicle_model_ptr_ = std::make_shared(
- vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0,
- accel_time_delay, accel_time_constant, brake_time_delay, brake_time_constant,
- steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, convert_brake_cmd,
- convert_steer_cmd, accel_map_path, brake_map_path, steer_map_path);
+ // init vehicle model depending on convert_steer_cmd_method
+ if (convert_steer_cmd) {
+ const std::string convert_steer_cmd_method =
+ declare_parameter("convert_steer_cmd_method");
+ if (convert_steer_cmd_method == "vgr") {
+ const double vgr_coef_a = declare_parameter("vgr_coef_a");
+ const double vgr_coef_b = declare_parameter("vgr_coef_b");
+ const double vgr_coef_c = declare_parameter("vgr_coef_c");
+ vehicle_model_ptr_ = std::make_shared(
+ vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase,
+ timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay,
+ brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd,
+ convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, vgr_coef_a,
+ vgr_coef_b, vgr_coef_c);
+ } else if (convert_steer_cmd_method == "steer_map") {
+ const std::string steer_map_path = declare_parameter("steer_map_path");
+ vehicle_model_ptr_ = std::make_shared(
+ vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase,
+ timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay,
+ brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd,
+ convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, steer_map_path);
+ } else {
+ throw std::invalid_argument(
+ "Invalid convert_steer_cmd_method: " + convert_steer_cmd_method);
+ }
+ }
} else {
throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str);
}
@@ -446,7 +471,6 @@ void SimplePlanningSimulator::on_timer()
publish_odometry(current_odometry_);
publish_pose(current_odometry_);
publish_velocity(current_velocity_);
- publish_steering(current_steer_);
publish_acceleration();
publish_imu();
@@ -455,6 +479,14 @@ void SimplePlanningSimulator::on_timer()
publish_turn_indicators_report();
publish_hazard_lights_report();
publish_tf(current_odometry_);
+
+ if (enable_pub_steer_) {
+ publish_steering(current_steer_);
+ }
+
+ if (vehicle_model_ptr_->shouldPublishActuationStatus()) {
+ publish_actuation_status();
+ }
}
void SimplePlanningSimulator::on_map(const LaneletMapBin::ConstSharedPtr msg)
@@ -871,6 +903,18 @@ void SimplePlanningSimulator::publish_tf(const Odometry & odometry)
tf_msg.transforms.emplace_back(std::move(tf));
pub_tf_->publish(tf_msg);
}
+
+void SimplePlanningSimulator::publish_actuation_status()
+{
+ auto actuation_status = vehicle_model_ptr_->getActuationStatus();
+ if (!actuation_status.has_value()) {
+ return;
+ }
+
+ actuation_status.value().header.stamp = get_clock()->now();
+ actuation_status.value().header.frame_id = simulated_frame_id_;
+ pub_actuation_status_->publish(actuation_status.value());
+}
} // namespace simple_planning_simulator
} // namespace simulation
diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp
index d550e335e2076..19794c04750fd 100644
--- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp
+++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp
@@ -50,6 +50,60 @@ double ActuationMap::getControlCommand(const double actuation, const double stat
return interpolation::lerp(actuation_index_, interpolated_control_vec, clamped_actuation);
}
+std::optional AccelMap::getThrottle(const double acc, double vel) const
+{
+ const std::vector & vel_indices = state_index_;
+ const std::vector & throttle_indices = actuation_index_;
+ const std::vector> & accel_map = actuation_map_;
+
+ std::vector interpolated_acc_vec;
+ const double clamped_vel = CSVLoader::clampValue(vel, vel_indices);
+
+ // (throttle, vel, acc) map => (throttle, acc) map by fixing vel
+ for (std::vector accelerations : accel_map) {
+ interpolated_acc_vec.push_back(interpolation::lerp(vel_indices, accelerations, clamped_vel));
+ }
+
+ // calculate throttle
+ // When the desired acceleration is smaller than the throttle area, return null => brake sequence
+ // When the desired acceleration is greater than the throttle area, return max throttle
+ if (acc < interpolated_acc_vec.front()) {
+ return std::nullopt;
+ } else if (interpolated_acc_vec.back() < acc) {
+ return throttle_indices.back();
+ }
+
+ return interpolation::lerp(interpolated_acc_vec, throttle_indices, acc);
+}
+
+double BrakeMap::getBrake(const double acc, double vel) const
+{
+ const std::vector & vel_indices = state_index_;
+ const std::vector & brake_indices = actuation_index_;
+ const std::vector> & brake_map = actuation_map_;
+
+ std::vector interpolated_acc_vec;
+ const double clamped_vel = CSVLoader::clampValue(vel, vel_indices);
+
+ // (brake, vel, acc) map => (brake, acc) map by fixing vel
+ for (std::vector accelerations : brake_map) {
+ interpolated_acc_vec.push_back(interpolation::lerp(vel_indices, accelerations, clamped_vel));
+ }
+
+ // calculate brake
+ // When the desired acceleration is smaller than the brake area, return max brake on the map
+ // When the desired acceleration is greater than the brake area, return min brake on the map
+ if (acc < interpolated_acc_vec.back()) {
+ return brake_indices.back();
+ } else if (interpolated_acc_vec.front() < acc) {
+ return brake_indices.front();
+ }
+
+ std::reverse(std::begin(interpolated_acc_vec), std::end(interpolated_acc_vec));
+ return interpolation::lerp(interpolated_acc_vec, brake_indices, acc);
+}
+
+// steer map sim model
SimModelActuationCmd::SimModelActuationCmd(
double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase,
double dt, double accel_delay, double accel_time_constant, double brake_delay,
@@ -75,6 +129,40 @@ SimModelActuationCmd::SimModelActuationCmd(
convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path);
convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path);
convert_steer_cmd_ = convert_steer_cmd && steer_map_.readActuationMapFromCSV(steer_map_path);
+ actuation_sim_type_ = ActuationSimType::STEER_MAP;
+}
+
+// VGR sim model
+SimModelActuationCmd::SimModelActuationCmd(
+ double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase,
+ double dt, double accel_delay, double accel_time_constant, double brake_delay,
+ double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias,
+ bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd,
+ std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b,
+ double vgr_coef_c)
+: SimModelInterface(6 /* dim x */, 5 /* dim u */),
+ MIN_TIME_CONSTANT(0.03),
+ vx_lim_(vx_lim),
+ vx_rate_lim_(vx_rate_lim),
+ steer_lim_(steer_lim),
+ steer_rate_lim_(steer_rate_lim),
+ wheelbase_(wheelbase),
+ accel_delay_(accel_delay),
+ accel_time_constant_(std::max(accel_time_constant, MIN_TIME_CONSTANT)),
+ brake_delay_(brake_delay),
+ brake_time_constant_(std::max(brake_time_constant, MIN_TIME_CONSTANT)),
+ steer_delay_(steer_delay),
+ steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)),
+ steer_bias_(steer_bias),
+ convert_steer_cmd_(convert_steer_cmd),
+ vgr_coef_a_(vgr_coef_a),
+ vgr_coef_b_(vgr_coef_b),
+ vgr_coef_c_(vgr_coef_c)
+{
+ initializeInputQueue(dt);
+ convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path);
+ convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path);
+ actuation_sim_type_ = ActuationSimType::VGR;
}
double SimModelActuationCmd::getX()
@@ -131,8 +219,9 @@ void SimModelActuationCmd::update(const double & dt)
const auto prev_state = state_;
updateRungeKutta(dt, delayed_input);
- // take velocity limit explicitly
- state_(IDX::VX) = std::max(-vx_lim_, std::min(state_(IDX::VX), vx_lim_));
+ // take velocity/steer limit explicitly
+ state_(IDX::VX) = std::clamp(state_(IDX::VX), -vx_lim_, vx_lim_);
+ state_(IDX::STEER) = std::clamp(state_(IDX::STEER), -steer_lim_, steer_lim_);
// consider gear
// update position and velocity first, and then acceleration is calculated naturally
@@ -201,8 +290,15 @@ Eigen::VectorXd SimModelActuationCmd::calcModel(
std::invoke([&]() -> double {
// if conversion is enabled, calculate steering rate from steer command
if (convert_steer_cmd_) {
- // convert steer command to steer rate
- return steer_map_.getControlCommand(input(IDX_U::STEER_DES), steer) / steer_time_constant_;
+ if (actuation_sim_type_ == ActuationSimType::VGR) {
+ // convert steer wheel command to steer rate
+ const double steer_des =
+ calculateSteeringTireCommand(vel, steer, input(IDX_U::STEER_DES));
+ return -(getSteer() - steer_des) / steer_time_constant_;
+ } else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) {
+ // convert steer command to steer rate
+ return steer_map_.getControlCommand(input(IDX_U::STEER_DES), vel) / steer_time_constant_;
+ }
}
// otherwise, steer command is desired steering angle, so calculate steering rate from the
// difference between the desired steering angle and the current steering angle.
@@ -258,3 +354,66 @@ void SimModelActuationCmd::updateStateWithGear(
state(IDX::ACCX) = (state(IDX::VX) - prev_state(IDX::VX)) / std::max(dt, 1.0e-5);
}
}
+
+std::optional
+SimModelActuationCmd::getActuationStatus() const
+{
+ if (!convert_accel_cmd_ && !convert_brake_cmd_ && !convert_steer_cmd_) {
+ return std::nullopt;
+ }
+
+ tier4_vehicle_msgs::msg::ActuationStatusStamped actuation_status;
+
+ const double acc_state = std::clamp(state_(IDX::ACCX), -vx_rate_lim_, vx_rate_lim_);
+ const double vel_state = std::clamp(state_(IDX::VX), -vx_lim_, vx_lim_);
+
+ if (convert_accel_cmd_) {
+ const auto throttle = accel_map_.getThrottle(acc_state, vel_state);
+ if (throttle.has_value()) {
+ actuation_status.status.accel_status = throttle.value();
+ }
+ }
+
+ if (convert_brake_cmd_) {
+ actuation_status.status.brake_status = brake_map_.getBrake(acc_state, vel_state);
+ }
+
+ if (convert_steer_cmd_) {
+ if (actuation_sim_type_ == ActuationSimType::VGR) {
+ actuation_status.status.steer_status =
+ calculateSteeringWheelState(vel_state, state_(IDX::STEER));
+ }
+ // NOTE: Conversion by steer map is not supported
+ // else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) {}
+ }
+
+ return actuation_status;
+}
+
+/* ------ Functions for VGR sim model ----- */
+double SimModelActuationCmd::calculateSteeringTireCommand(
+ const double vel, const double steer, const double steer_wheel_des) const
+{
+ // steer_tire_state -> steer_wheel_state
+ const double steer_wheel = calculateSteeringWheelState(vel, steer);
+
+ // steer_wheel_des -> steer_tire_des
+ const double adaptive_gear_ratio = calculateVariableGearRatio(vel, steer_wheel);
+
+ return steer_wheel_des / adaptive_gear_ratio;
+}
+
+double SimModelActuationCmd::calculateSteeringWheelState(
+ const double vel, const double steer_state) const
+{
+ return (vgr_coef_a_ + vgr_coef_b_ * vel * vel) * steer_state /
+ (1.0 + vgr_coef_c_ * std::abs(steer_state));
+}
+
+double SimModelActuationCmd::calculateVariableGearRatio(
+ const double vel, const double steer_wheel) const
+{
+ return std::max(
+ 1e-5, vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs(steer_wheel));
+}
+/* ---------------------------------------- */
diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp
index 73762150f8e1d..cb58628121de2 100644
--- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp
+++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp
@@ -265,10 +265,31 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options)
node_options.append_parameter_override("max_steer_angle", 0.7);
}
+using DefaultParamType = std::tuple;
+using ActuationCmdParamType = std::tuple;
+using ParamType = std::variant;
+std::unordered_map vehicle_model_type_map = {
+ {"IDEAL_STEER_VEL", typeid(DefaultParamType)},
+ {"IDEAL_STEER_ACC", typeid(DefaultParamType)},
+ {"IDEAL_STEER_ACC_GEARED", typeid(DefaultParamType)},
+ {"DELAY_STEER_VEL", typeid(DefaultParamType)},
+ {"DELAY_STEER_ACC", typeid(DefaultParamType)},
+ {"DELAY_STEER_ACC_GEARED", typeid(DefaultParamType)},
+ {"DELAY_STEER_ACC_GEARED_WO_FALL_GUARD", typeid(DefaultParamType)},
+ {"ACTUATION_CMD", typeid(ActuationCmdParamType)}};
+
+std::pair get_common_params(const ParamType & params)
+{
+ return std::visit(
+ [](const auto & param) -> std::pair {
+ return std::make_pair(std::get<0>(param), std::get<1>(param));
+ },
+ params);
+}
+
// Send a control command and run the simulation.
// Then check if the vehicle is moving in the desired direction.
-class TestSimplePlanningSimulator
-: public ::testing::TestWithParam>
+class TestSimplePlanningSimulator : public ::testing::TestWithParam
{
};
@@ -277,10 +298,23 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel)
rclcpp::init(0, nullptr);
const auto params = GetParam();
- const auto command_type = std::get<0>(params);
- const auto vehicle_model_type = std::get<1>(params);
-
+ // common parameters
+ const auto common_params = get_common_params(params);
+ const auto command_type = common_params.first;
+ const auto vehicle_model_type = common_params.second;
std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl;
+ // optional parameters
+ std::optional conversion_type{}; // for ActuationCmdParamType
+
+ // Determine the ParamType corresponding to vehicle_model_type and get the specific parameters.
+ const auto iter = vehicle_model_type_map.find(vehicle_model_type);
+ if (iter == vehicle_model_type_map.end()) {
+ throw std::invalid_argument("Unexpected vehicle_model_type.");
+ }
+ if (iter->second == typeid(ActuationCmdParamType)) {
+ conversion_type = std::get<2>(std::get(params));
+ }
+
rclcpp::NodeOptions node_options;
node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC");
node_options.append_parameter_override("vehicle_model_type", vehicle_model_type);
@@ -300,6 +334,12 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel)
node_options.append_parameter_override("accel_map_path", accel_map_path);
node_options.append_parameter_override("brake_map_path", brake_map_path);
node_options.append_parameter_override("steer_map_path", steer_map_path);
+ node_options.append_parameter_override("vgr_coef_a", 15.713);
+ node_options.append_parameter_override("vgr_coef_b", 0.053);
+ node_options.append_parameter_override("vgr_coef_c", 0.042);
+ if (conversion_type.has_value()) {
+ node_options.append_parameter_override("convert_steer_cmd_method", conversion_type.value());
+ }
declareVehicleInfoParams(node_options);
const auto sim_node = std::make_shared(node_options);
@@ -393,4 +433,5 @@ INSTANTIATE_TEST_SUITE_P(
std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED"),
std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED_WO_FALL_GUARD"),
/* Actuation type */
- std::make_tuple(CommandType::Actuation, "ACTUATION_CMD")));
+ std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "steer_map"),
+ std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "vgr")));
From ecc9586c5c00a767fb891caa8c7341e4995fdea5 Mon Sep 17 00:00:00 2001
From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com>
Date: Thu, 22 Aug 2024 14:23:05 +0900
Subject: [PATCH 007/169] feat(build-and-test-differential): skip cuda build
when tag:require-cuda-build-and-test is not attached (#8562)
* feat(build-and-test-differential): skip cuda build when tag:require-cuda-build-and-test is not attached
Signed-off-by: Y.Hisaki
* fix miss
Signed-off-by: Y.Hisaki
* for debugging
Signed-off-by: Y.Hisaki
* fix bug
Signed-off-by: Y.Hisaki
* remove debug code
Signed-off-by: Y.Hisaki
---------
Signed-off-by: Y.Hisaki
---
.github/workflows/build-and-test-differential.yaml | 8 +++++++-
1 file changed, 7 insertions(+), 1 deletion(-)
diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml
index 48d432861f1de..5e1f3e2c093a5 100644
--- a/.github/workflows/build-and-test-differential.yaml
+++ b/.github/workflows/build-and-test-differential.yaml
@@ -22,8 +22,13 @@ jobs:
with:
label: tag:run-build-and-test-differential
+ make-sure-require-cuda-label-is-present:
+ uses: autowarefoundation/autoware-github-actions/.github/workflows/make-sure-label-is-present.yaml@v1
+ with:
+ label: tag:require-cuda-build-and-test
+
build-and-test-differential:
- needs: make-sure-label-is-present
+ needs: [make-sure-label-is-present, make-sure-require-cuda-label-is-present]
if: ${{ needs.make-sure-label-is-present.outputs.result == 'true' }}
runs-on: ${{ matrix.runner }}
container: ${{ matrix.container }}${{ matrix.container-suffix }}
@@ -57,6 +62,7 @@ jobs:
fetch-depth: ${{ env.PR_FETCH_DEPTH }}
- name: Run build-and-test-differential action
+ if: ${{ !(matrix.container-suffix == '-cuda') || needs.make-sure-require-cuda-label-is-present.outputs.result == 'true' }}
uses: ./.github/actions/build-and-test-differential
with:
rosdistro: ${{ matrix.rosdistro }}
From 9819971f6631af950f5cb9fc70b27aadd13dfe29 Mon Sep 17 00:00:00 2001
From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com>
Date: Thu, 22 Aug 2024 15:11:19 +0900
Subject: [PATCH 008/169] refactor(autoware_pointcloud_preprocessor): rework
concatenate_pointcloud and time_synchronizer_node parameters (#8509)
* feat: rewort concatenate pointclouds and time synchronizer parameter
Signed-off-by: vividf
* chore: fix launch files
Signed-off-by: vividf
* chore: fix schema
Signed-off-by: vividf
* chore: fix schema
Signed-off-by: vividf
* chore: fix integer and number default value in schema
Signed-off-by: vividf
* chore: add boundary
Signed-off-by: vividf
---------
Signed-off-by: vividf
---
.../CMakeLists.txt | 2 +-
.../config/concatenate_pointclouds.param.yaml | 11 +++
.../config/time_synchronizer_node.param.yaml | 14 ++++
.../concatenate_pointclouds.hpp | 2 +-
...nodelet.hpp => time_synchronizer_node.hpp} | 8 +-
.../launch/concatenate_pointcloud.launch.xml | 9 ++
.../launch/time_synchronizer_node.launch.xml | 9 ++
.../concatenate_pointclouds.schema.json | 58 +++++++++++++
.../schema/time_synchronizer_node.schema.json | 83 +++++++++++++++++++
.../concatenate_pointclouds.cpp | 12 +--
...nodelet.cpp => time_synchronizer_node.cpp} | 19 ++---
11 files changed, 205 insertions(+), 22 deletions(-)
create mode 100644 sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml
create mode 100644 sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml
rename sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/{time_synchronizer_nodelet.hpp => time_synchronizer_node.hpp} (98%)
create mode 100644 sensing/autoware_pointcloud_preprocessor/launch/concatenate_pointcloud.launch.xml
create mode 100644 sensing/autoware_pointcloud_preprocessor/launch/time_synchronizer_node.launch.xml
create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/concatenate_pointclouds.schema.json
create mode 100644 sensing/autoware_pointcloud_preprocessor/schema/time_synchronizer_node.schema.json
rename sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/{time_synchronizer_nodelet.cpp => time_synchronizer_node.cpp} (97%)
diff --git a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
index f39e45d4ea72e..11d774bffbccf 100644
--- a/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
+++ b/sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
@@ -64,7 +64,7 @@ ament_target_dependencies(faster_voxel_grid_downsample_filter
ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/concatenate_data/concatenate_and_time_sync_nodelet.cpp
src/concatenate_data/concatenate_pointclouds.cpp
- src/time_synchronizer/time_synchronizer_nodelet.cpp
+ src/time_synchronizer/time_synchronizer_node.cpp
src/crop_box_filter/crop_box_filter_nodelet.cpp
src/downsample_filter/voxel_grid_downsample_filter_node.cpp
src/downsample_filter/random_downsample_filter_nodelet.cpp
diff --git a/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml
new file mode 100644
index 0000000000000..5d38186840057
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/config/concatenate_pointclouds.param.yaml
@@ -0,0 +1,11 @@
+/**:
+ ros__parameters:
+ output_frame: base_link
+ input_topics: [
+ "/sensing/lidar/left/pointcloud_before_sync",
+ "/sensing/lidar/right/pointcloud_before_sync",
+ "/sensing/lidar/top/pointcloud_before_sync"
+ ]
+ max_queue_size: 5
+ timeout_sec: 0.033
+ input_offset: [0.0 ,0.0 ,0.0]
diff --git a/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml
new file mode 100644
index 0000000000000..9add0be3f8809
--- /dev/null
+++ b/sensing/autoware_pointcloud_preprocessor/config/time_synchronizer_node.param.yaml
@@ -0,0 +1,14 @@
+/**:
+ ros__parameters:
+ input_twist_topic_type: twist
+ output_frame: base_link
+ keep_input_frame_in_synchronized_pointcloud: false
+ input_topics: [
+ "/sensing/lidar/left/pointcloud_before_sync",
+ "/sensing/lidar/right/pointcloud_before_sync",
+ "/sensing/lidar/top/pointcloud_before_sync"
+ ]
+ synchronized_pointcloud_postfix: pointcloud
+ max_queue_size: 5
+ timeout_sec: 0.033
+ input_offset: [0.0, 0.0, 0.0]
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp
index b982553a8c920..9711025b713df 100644
--- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp
+++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp
@@ -1,4 +1,4 @@
-// Copyright 2023 TIER IV, Inc.
+// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp
similarity index 98%
rename from sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp
rename to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp
index 4f08ae3a3ce67..ad5cde3056ef0 100644
--- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_nodelet.hpp
+++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp
@@ -1,4 +1,4 @@
-// Copyright 2023 TIER IV, Inc.
+// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
@@ -49,8 +49,8 @@
*
*/
-#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_
-#define AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODELET_HPP_
+#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODE_HPP_
+#define AUTOWARE__POINTCLOUD_PREPROCESSOR__TIME_SYNCHRONIZER__TIME_SYNCHRONIZER_NODE_HPP_
#include
#include