Skip to content

Commit a5b62af

Browse files
asa-nakiTakaHoribepre-commit-ci[bot]sfukutah-ohta
authored
feat: resource check (#1496)
* feat(system_error_monitor): manual modules (#793) * feat(rviz_plugin): console meter is too large on the Rviz with FHD display, isn't it? (#587) * feat(tier4_planning/vehicle_plugin): make plugins size scalable Signed-off-by: Takamasa Horibe <[email protected]> * remove space Signed-off-by: Takamasa Horibe <[email protected]> * scaling Signed-off-by: Takamasa Horibe <[email protected]> * change diag message Signed-off-by: asa-naki <[email protected]> * fix module name Signed-off-by: asa-naki <[email protected]> * add manual module and ignoring modules Signed-off-by: asa-naki <[email protected]> * Revert "feat(rviz_plugin): console meter is too large on the Rviz with FHD display, isn't it? (#587)" This reverts commit f96169c. * Revert "change diag message" This reverts commit dff01ce. * ci(pre-commit): autofix * fix spell check Signed-off-by: asa-naki <[email protected]> * Revert "fix spell check" This reverts commit 208aa1e. * Revert "fix module name" This reverts commit cec7653. * revert ignore module Signed-off-by: asa-naki <[email protected]> * current_mode check update Signed-off-by: asa-naki <[email protected]> * ci(pre-commit): autofix * delete margin Signed-off-by: asa-naki <[email protected]> --------- Signed-off-by: Takamasa Horibe <[email protected]> Signed-off-by: asa-naki <[email protected]> Co-authored-by: Takamasa Horibe <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(ad_service_state_monitor): change configs name (#876) change configs name Signed-off-by: asa-naki <[email protected]> * feat(plannig_error_monitor): update error sharp angle threshold (#681) * fix error_sharp_angle Signed-off-by: Shigekazu Fukuta <[email protected]> * update readme Signed-off-by: Shigekazu Fukuta <[email protected]> --------- Signed-off-by: Shigekazu Fukuta <[email protected]> * fix: add error handling when path is invalid (#934) * fix(behavior_path): delete duplicated * add error handling * fix: when path size is 1 * fix(detection_area): search collision index only in lanelet (#695) * fix(detection_area): search collision index only in lanelet * ci(pre-commit): autofix --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(detection_area): fix overline function (#930) * fix(detection_area): fix overline function * ci(pre-commit): autofix --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(route_handler): fix threshold for removing overlapping points (#1015) * fix(route_handler): fix threshold for removing overlapping points * fix * fix(ntp_monitor): move chronyc command execution to a timer (backport autowarefoundation#4634) (#880) fix(ntp_monitor): move chronyc command execution to a timer (autowarefoundation#4634) * fix(ntp_monitor): move chronyc command execution to a timer * add newly added parameter timeout to config --------- Signed-off-by: ito-san <[email protected]> Co-authored-by: ito-san <[email protected]> * feat(elevation_map_loader): add error handling for std::runtime_error (backport autowarefoundation#4187) (#652) feat(elevation_map_loader): add error handling for std::runtime_error (autowarefoundation#4187) * feat(elevation_map_loader): Add error handling for std::runtime_error * feat(elevation_map_loader): add error message output --------- Signed-off-by: Shin-kyoto <[email protected]> Co-authored-by: Shintaro Tomie <[email protected]> * fix(system_monitor): extend command line to display (backport autowarefoundation#4553) (#768) fix(system_monitor): extend command line to display (autowarefoundation#4553) Signed-off-by: ito-san <[email protected]> Co-authored-by: ito-san <[email protected]> * fix(system_monitor): high-memory process are not provided in MEM order (backport autowarefoundation#4654) (#769) fix(system_monitor): high-memory process are not provided in MEM order (autowarefoundation#4654) * fix(process_monitor): high-memory process are not being provided in %MEM order * changed option from 'g' to 'n' --------- Signed-off-by: ito-san <[email protected]> Co-authored-by: ito-san <[email protected]> * fix(system_monitor): fix program command line reading (backport autowarefoundation#5191, autowarefoundation#5430) (#995) * perf(system_monitor): fix program command line reading (autowarefoundation#5191) * Fix program command line reading Signed-off-by: Owen-Liuyuxuan <[email protected]> * style(pre-commit): autofix * fix spelling commandline->command_line Signed-off-by: Owen-Liuyuxuan <[email protected]> --------- Signed-off-by: Owen-Liuyuxuan <[email protected]> Co-authored-by: Owen-Liuyuxuan <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(system_monitor): output command line (autowarefoundation#5430) * fix(system_monitor): output command line Signed-off-by: takeshi.iwanari <[email protected]> * style(pre-commit): autofix --------- Signed-off-by: takeshi.iwanari <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --------- Signed-off-by: Owen-Liuyuxuan <[email protected]> Signed-off-by: takeshi.iwanari <[email protected]> Co-authored-by: Yuxuan Liu <[email protected]> Co-authored-by: Owen-Liuyuxuan <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: takeshi-iwanari <[email protected]> Co-authored-by: Akihisa Nagata <[email protected]> * feat(imu_corrector): add gyro_bias_validator (backport autowarefoundation#4729) (#856) * feat(imu_corrector): add gyro_bias_validator (backport autowarefoundation#4729) * feat(imu_corrector): add gyro_bias_validator Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * update Signed-off-by: kminoda <[email protected]> * revert launch Signed-off-by: kminoda <[email protected]> * updat Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * add debug publisher Signed-off-by: kminoda <[email protected]> * minor fix Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * style(pre-commit): autofix * add gtest Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * updat e readme Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * add diagnostics Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * update Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * validator -> estimator Signed-off-by: kminoda <[email protected]> * fix build Signed-off-by: kminoda <[email protected]> * update default parameter Signed-off-by: kminoda <[email protected]> * update comment Signed-off-by: kminoda <[email protected]> * update readme Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * updated Signed-off-by: kminoda <[email protected]> * minor update in readme Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * fix pre-commit Signed-off-by: kminoda <[email protected]> * update readme Signed-off-by: kminoda <[email protected]> * style(pre-commit): autofix * Fix NG -> WARN Signed-off-by: kminoda <[email protected]> --------- Signed-off-by: kminoda <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: asa-naki <[email protected]> * build(imu_corrector): add missing diagnostic_updater dependency (autowarefoundation#4980) Signed-off-by: Esteve Fernandez <[email protected]> * add gyro_bias estimation in diag ( autowarefoundation#5054) Signed-off-by: asa-naki <[email protected]> * ci(pre-commit): autofix --------- Signed-off-by: asa-naki <[email protected]> Signed-off-by: Esteve Fernandez <[email protected]> Co-authored-by: kminoda <[email protected]> Co-authored-by: Esteve Fernandez <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(imu_corrector): add gyro bias log (#918) add gyro_bias log Signed-off-by: asa-naki <[email protected]> * feat(system_error_monitor): add ignore_until_waiting_for_route module (#888) * add ignore_module Signed-off-by: asa-naki <[email protected]> * add description Signed-off-by: asa-naki <[email protected]> * ci(pre-commit): autofix * change name ignore_until_waiting_for_route Signed-off-by: asa-naki <[email protected]> * update description Signed-off-by: asa-naki <[email protected]> * rename function name and delete planning state Signed-off-by: asa-naki <[email protected]> * update description Signed-off-by: asa-naki <[email protected]> * Update --------- Signed-off-by: asa-naki <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Hiroki OTA <[email protected]> * feat(system_error_monitor): add ignore hartbeat timeout in initializing state (#972) * add ignore hartbeat timeout in initializing state Signed-off-by: asa-naki <[email protected]> * fix typo * Update comment * ci(pre-commit): autofix * fix typo * ci(pre-commit): autofix * update comment * ci(pre-commit): autofix --------- Signed-off-by: asa-naki <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --------- Signed-off-by: Takamasa Horibe <[email protected]> Signed-off-by: asa-naki <[email protected]> Signed-off-by: Shigekazu Fukuta <[email protected]> Signed-off-by: ito-san <[email protected]> Signed-off-by: Shin-kyoto <[email protected]> Signed-off-by: Owen-Liuyuxuan <[email protected]> Signed-off-by: takeshi.iwanari <[email protected]> Signed-off-by: Esteve Fernandez <[email protected]> Co-authored-by: Takamasa Horibe <[email protected]> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shigekazu Fukuta <[email protected]> Co-authored-by: Hiroki OTA <[email protected]> Co-authored-by: ito-san <[email protected]> Co-authored-by: Shintaro Tomie <[email protected]> Co-authored-by: Yuxuan Liu <[email protected]> Co-authored-by: Owen-Liuyuxuan <[email protected]> Co-authored-by: takeshi-iwanari <[email protected]> Co-authored-by: kminoda <[email protected]> Co-authored-by: Esteve Fernandez <[email protected]>
1 parent 07d0687 commit a5b62af

File tree

34 files changed

+771
-190
lines changed

34 files changed

+771
-190
lines changed

perception/elevation_map_loader/src/elevation_map_loader_node.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,8 @@ void ElevationMapLoaderNode::publish()
102102
try {
103103
is_bag_loaded = grid_map::GridMapRosConverter::loadFromBag(
104104
*data_manager_.elevation_map_path_, "elevation_map", elevation_map_);
105-
} catch (rosbag2_storage_plugins::SqliteException & e) {
105+
} catch (const std::runtime_error & e) {
106+
RCLCPP_ERROR(this->get_logger(), e.what());
106107
is_bag_loaded = false;
107108
}
108109
if (!is_bag_loaded) {

planning/behavior_path_planner/src/utilities.cpp

-23
Original file line numberDiff line numberDiff line change
@@ -26,29 +26,6 @@
2626
#include <string>
2727
#include <vector>
2828

29-
namespace tier4_autoware_utils
30-
{
31-
template <class T>
32-
double calcLateralOffset(
33-
const T & points, const geometry_msgs::msg::Point & p_target, const size_t seg_idx)
34-
{
35-
validateNonEmpty(points);
36-
37-
const auto p_front = getPoint(points.at(seg_idx));
38-
const auto p_back = getPoint(points.at(seg_idx + 1));
39-
40-
const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0};
41-
const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0};
42-
43-
if (segment_vec.norm() == 0.0) {
44-
throw std::runtime_error("Same points are given.");
45-
}
46-
47-
const Eigen::Vector3d cross_vec = segment_vec.cross(target_vec);
48-
return cross_vec(2) / segment_vec.norm();
49-
}
50-
} // namespace tier4_autoware_utils
51-
5229
namespace drivable_area_utils
5330
{
5431
double quantize(const double val, const double resolution)

planning/behavior_velocity_planner/include/scene_module/detection_area/scene.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,8 @@ class DetectionAreaModule : public SceneModuleInterface
6262

6363
public:
6464
DetectionAreaModule(
65-
const int64_t module_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem,
65+
const int64_t module_id, const size_t lane_id,
66+
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
6667
const PlannerParam & planner_param, const rclcpp::Logger logger,
6768
const rclcpp::Clock::SharedPtr clock);
6869

@@ -106,6 +107,8 @@ class DetectionAreaModule : public SceneModuleInterface
106107

107108
// Debug
108109
DebugData debug_data_;
110+
111+
int64_t lane_id_;
109112
};
110113
} // namespace behavior_velocity_planner
111114

planning/behavior_velocity_planner/src/scene_module/detection_area/manager.cpp

+12-9
Original file line numberDiff line numberDiff line change
@@ -28,22 +28,24 @@ namespace behavior_velocity_planner
2828
{
2929
namespace
3030
{
31-
std::vector<lanelet::DetectionAreaConstPtr> getDetectionAreaRegElemsOnPath(
31+
using DetectionAreaWithLaneId = std::pair<lanelet::DetectionAreaConstPtr, int64_t>;
32+
33+
std::vector<DetectionAreaWithLaneId> getDetectionAreaRegElemsOnPath(
3234
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
3335
const lanelet::LaneletMapPtr lanelet_map)
3436
{
35-
std::vector<lanelet::DetectionAreaConstPtr> detection_area_reg_elems;
37+
std::vector<DetectionAreaWithLaneId> detection_areas_with_lane_id;
3638

3739
for (const auto & p : path.points) {
3840
const auto lane_id = p.lane_ids.at(0);
3941
const auto ll = lanelet_map->laneletLayer.get(lane_id);
4042
const auto detection_areas = ll.regulatoryElementsAs<const lanelet::autoware::DetectionArea>();
4143
for (const auto & detection_area : detection_areas) {
42-
detection_area_reg_elems.push_back(detection_area);
44+
detection_areas_with_lane_id.push_back(std::make_pair(detection_area, lane_id));
4345
}
4446
}
4547

46-
return detection_area_reg_elems;
48+
return detection_areas_with_lane_id;
4749
}
4850

4951
std::set<int64_t> getDetectionAreaIdSetOnPath(
@@ -52,7 +54,7 @@ std::set<int64_t> getDetectionAreaIdSetOnPath(
5254
{
5355
std::set<int64_t> detection_area_id_set;
5456
for (const auto & detection_area : getDetectionAreaRegElemsOnPath(path, lanelet_map)) {
55-
detection_area_id_set.insert(detection_area->id());
57+
detection_area_id_set.insert(detection_area.first->id());
5658
}
5759
return detection_area_id_set;
5860
}
@@ -72,14 +74,15 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
7274
void DetectionAreaModuleManager::launchNewModules(
7375
const autoware_auto_planning_msgs::msg::PathWithLaneId & path)
7476
{
75-
for (const auto & detection_area :
77+
for (const auto & detection_area_with_lane_id :
7678
getDetectionAreaRegElemsOnPath(path, planner_data_->route_handler_->getLaneletMapPtr())) {
7779
// Use lanelet_id to unregister module when the route is changed
78-
const auto module_id = detection_area->id();
80+
const auto module_id = detection_area_with_lane_id.first->id();
81+
const auto lane_id = detection_area_with_lane_id.second;
7982
if (!isModuleRegistered(module_id)) {
8083
registerModule(std::make_shared<DetectionAreaModule>(
81-
module_id, *detection_area, planner_param_, logger_.get_child("detection_area_module"),
82-
clock_));
84+
module_id, lane_id, *(detection_area_with_lane_id.first), planner_param_,
85+
logger_.get_child("detection_area_module"), clock_));
8386
}
8487
}
8588
}

planning/behavior_velocity_planner/src/scene_module/detection_area/scene.cpp

+20-7
Original file line numberDiff line numberDiff line change
@@ -69,9 +69,13 @@ boost::optional<Point2d> getNearestCollisionPoint(
6969
}
7070

7171
boost::optional<PathIndexWithPoint2d> findCollisionSegment(
72-
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line)
72+
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line,
73+
const SearchRangeIndex & search_index)
7374
{
74-
for (size_t i = 0; i < path.points.size() - 1; ++i) {
75+
const auto min_search_index = std::max(static_cast<size_t>(0), search_index.min_idx);
76+
const auto max_search_index = std::min(search_index.max_idx, path.points.size() - 1);
77+
78+
for (size_t i = min_search_index; i < max_search_index; ++i) {
7579
const auto & p1 = path.points.at(i).point.pose.position; // Point before collision point
7680
const auto & p2 = path.points.at(i + 1).point.pose.position; // Point after collision point
7781

@@ -186,13 +190,15 @@ geometry_msgs::msg::Pose calcTargetPose(
186190
} // namespace
187191

188192
DetectionAreaModule::DetectionAreaModule(
189-
const int64_t module_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem,
193+
const int64_t module_id, const size_t lane_id,
194+
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
190195
const PlannerParam & planner_param, const rclcpp::Logger logger,
191196
const rclcpp::Clock::SharedPtr clock)
192197
: SceneModuleInterface(module_id, logger, clock),
193198
detection_area_reg_elem_(detection_area_reg_elem),
194199
state_(State::GO),
195-
planner_param_(planner_param)
200+
planner_param_(planner_param),
201+
lane_id_(lane_id)
196202
{
197203
}
198204

@@ -351,8 +357,13 @@ bool DetectionAreaModule::isOverLine(
351357
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
352358
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const
353359
{
354-
return tier4_autoware_utils::calcSignedArcLength(
355-
path.points, self_pose.position, line_pose.position) < 0;
360+
const PointWithSearchRangeIndex src_point_with_search_range_index =
361+
planning_utils::findFirstNearSearchRangeIndex(path.points, self_pose.position);
362+
const PointWithSearchRangeIndex dst_point_with_search_range_index = {
363+
line_pose.position, planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_)};
364+
365+
return planning_utils::calcSignedArcLengthWithSearchIndex(
366+
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) < 0;
356367
}
357368

358369
bool DetectionAreaModule::hasEnoughBrakingDistance(
@@ -392,8 +403,10 @@ boost::optional<PathIndexWithPose> DetectionAreaModule::createTargetPoint(
392403
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line,
393404
const double margin) const
394405
{
406+
const auto dst_search_range = planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_);
407+
395408
// Find collision segment
396-
const auto collision_segment = findCollisionSegment(path, stop_line);
409+
const auto collision_segment = findCollisionSegment(path, stop_line, dst_search_range);
397410
if (!collision_segment) {
398411
// No collision
399412
return {};

planning/obstacle_avoidance_planner/include/obstacle_avoidance_planner/node.hpp

+12
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,10 @@ template <typename T>
5353
boost::optional<geometry_msgs::msg::Pose> lerpPose(
5454
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
5555
{
56+
if (points.size() < 2) {
57+
return {};
58+
}
59+
5660
constexpr double epsilon = 1e-6;
5761

5862
const double closest_to_target_dist =
@@ -94,6 +98,10 @@ template <typename T>
9498
double lerpTwistX(
9599
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
96100
{
101+
if (points.size() < 2) {
102+
return 0.0;
103+
}
104+
97105
constexpr double epsilon = 1e-6;
98106

99107
const double closest_to_target_dist =
@@ -116,6 +124,10 @@ template <typename T>
116124
double lerpPoseZ(
117125
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
118126
{
127+
if (points.size() < 2) {
128+
return 0.0;
129+
}
130+
119131
constexpr double epsilon = 1e-6;
120132

121133
const double closest_to_target_dist =

planning/obstacle_avoidance_planner/src/node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -1093,6 +1093,9 @@ void ObstacleAvoidancePlanner::calcVelocity(
10931093
const std::vector<autoware_auto_planning_msgs::msg::PathPoint> & path_points,
10941094
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & traj_points) const
10951095
{
1096+
if (path_points.size() < 2) {
1097+
return;
1098+
}
10961099
for (size_t i = 0; i < traj_points.size(); i++) {
10971100
const size_t nearest_seg_idx = [&]() {
10981101
const auto opt_seg_idx = tier4_autoware_utils::findNearestSegmentIndex(

planning/obstacle_stop_planner/src/node.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -753,6 +753,10 @@ void ObstacleStopPlannerNode::insertVelocity(
753753
const std_msgs::msg::Header & trajectory_header, const VehicleInfo & vehicle_info,
754754
const double current_acc, const double current_vel, const StopParam & stop_param)
755755
{
756+
if (output.size() < 3) {
757+
return;
758+
}
759+
756760
if (planner_data.stop_require) {
757761
// insert stop point
758762
const auto traj_end_idx = output.size() - 1;

planning/planning_error_monitor/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ This function checks if the relative angle at point1 generated from point2 and 3
4747
| :------------------------ | :------- | :------------------------------------ | :------------ |
4848
| `error_interval` | `double` | Error Interval Distance Threshold [m] | 100.0 |
4949
| `error_curvature` | `double` | Error Curvature Threshold | 1.0 |
50-
| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | $\pi$/4 |
50+
| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | 2.0 |
5151
| `ignore_too_close_points` | `double` | Ignore Too Close Distance Threshold | 0.005 |
5252

5353
## Visualization

planning/planning_error_monitor/launch/planning_error_monitor.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
<remap from="~/input/trajectory" to="$(var input/trajectory)"/>
1010
<param name="error_interval" value="100.0"/>
1111
<param name="error_curvature" value="2.0"/>
12-
<param name="error_sharp_angle" value="0.785398"/>
12+
<param name="error_sharp_angle" value="2.0"/>
1313
<param name="ignore_too_close_points" value="0.01"/>
1414
</node>
1515
</launch>

planning/route_handler/src/route_handler.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path)
121121
continue;
122122
}
123123

124-
constexpr double min_dist = 0.001;
124+
constexpr double min_dist = 0.1;
125125
if (
126126
tier4_autoware_utils::calcDistance3d(filtered_path.points.back().point, pt.point) <
127127
min_dist) {

sensing/imu_corrector/CMakeLists.txt

+24-1
Original file line numberDiff line numberDiff line change
@@ -14,19 +14,42 @@ endif()
1414
find_package(ament_cmake_auto REQUIRED)
1515
ament_auto_find_build_dependencies()
1616

17+
ament_auto_add_library(gyro_bias_estimation_module SHARED
18+
src/gyro_bias_estimation_module.cpp
19+
)
20+
1721
ament_auto_add_library(imu_corrector_node SHARED
1822
src/imu_corrector_core.cpp
19-
include/imu_corrector/imu_corrector_core.hpp
2023
)
2124

25+
ament_auto_add_library(gyro_bias_estimator_node SHARED
26+
src/gyro_bias_estimator.cpp
27+
)
28+
29+
target_link_libraries(gyro_bias_estimator_node gyro_bias_estimation_module)
30+
2231
rclcpp_components_register_node(imu_corrector_node
2332
PLUGIN "imu_corrector::ImuCorrector"
2433
EXECUTABLE imu_corrector
2534
)
2635

36+
rclcpp_components_register_node(gyro_bias_estimator_node
37+
PLUGIN "imu_corrector::GyroBiasEstimator"
38+
EXECUTABLE gyro_bias_estimator
39+
)
40+
41+
function(add_testcase filepath)
42+
get_filename_component(filename ${filepath} NAME)
43+
string(REGEX REPLACE ".cpp" "" test_name ${filename})
44+
ament_add_gmock(${test_name} ${filepath})
45+
target_link_libraries("${test_name}" gyro_bias_estimation_module imu_corrector_node gyro_bias_estimator_node)
46+
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
47+
endfunction()
48+
2749
if(BUILD_TESTING)
2850
find_package(ament_lint_auto REQUIRED)
2951
ament_lint_auto_find_test_dependencies()
52+
add_testcase(test/test_gyro_bias_estimation_module.cpp)
3053
endif()
3154

3255
ament_auto_package(INSTALL_TO_SHARE

sensing/imu_corrector/README.md

+28-11
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
# imu_corrector
22

3-
## Purpose
3+
## imu_corrector
44

55
`imu_corrector_node` is a node that correct imu data.
66

@@ -10,8 +10,6 @@
1010
<!-- TODO(TIER IV): Make this repository public or change the link. -->
1111
<!-- Use the value estimated by [deviation_estimator](https://github.com/tier4/calibration_tools/tree/main/localization/deviation_estimation_tools) as the parameters for this node. -->
1212

13-
## Inputs / Outputs
14-
1513
### Input
1614

1715
| Name | Type | Description |
@@ -24,9 +22,7 @@
2422
| --------- | ----------------------- | ------------------ |
2523
| `~output` | `sensor_msgs::msg::Imu` | corrected imu data |
2624

27-
## Parameters
28-
29-
### Core Parameters
25+
### Parameters
3026

3127
| Name | Type | Description |
3228
| ---------------------------- | ------ | ------------------------------------- |
@@ -37,12 +33,33 @@
3733
| `angular_velocity_stddev_yy` | double | pitch rate standard deviation [rad/s] |
3834
| `angular_velocity_stddev_zz` | double | yaw rate standard deviation [rad/s] |
3935

40-
## Assumptions / Known limits
36+
## gyro_bias_estimator
37+
38+
`gyro_bias_validator` is a node that validates the bias of the gyroscope. It subscribes to the `sensor_msgs::msg::Imu` topic and validate if the bias of the gyroscope is within the specified range.
4139

42-
## (Optional) Error detection and handling
40+
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
4341

44-
## (Optional) Performance characterization
42+
### Input
43+
44+
| Name | Type | Description |
45+
| ----------------- | ------------------------------------------------ | ---------------- |
46+
| `~/input/imu_raw` | `sensor_msgs::msg::Imu` | **raw** imu data |
47+
| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | vehicle velocity |
4548

46-
## (Optional) References/External links
49+
### Output
4750

48-
## (Optional) Future extensions / Unimplemented parts
51+
| Name | Type | Description |
52+
| -------------------- | ------------------------------------ | ----------------------------- |
53+
| `~/output/gyro_bias` | `geometry_msgs::msg::Vector3Stamped` | bias of the gyroscope [rad/s] |
54+
55+
### Parameters
56+
57+
| Name | Type | Description |
58+
| --------------------------- | ------ | ----------------------------------------------------------------------------- |
59+
| `angular_velocity_offset_x` | double | roll rate offset in imu_link [rad/s] |
60+
| `angular_velocity_offset_y` | double | pitch rate offset imu_link [rad/s] |
61+
| `angular_velocity_offset_z` | double | yaw rate offset imu_link [rad/s] |
62+
| `gyro_bias_threshold` | double | threshold of the bias of the gyroscope [rad/s] |
63+
| `velocity_threshold` | double | threshold of the vehicle velocity to determine if the vehicle is stopped[m/s] |
64+
| `timestamp_threshold` | double | threshold of the timestamp diff between IMU and twist [s] |
65+
| `data_num_threshold` | int | number of data used to calculate bias |
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
/**:
2+
ros__parameters:
3+
gyro_bias_threshold: 0.0015 # [rad/s]
4+
velocity_threshold: 0.0 # [m/s]
5+
timestamp_threshold: 0.1 # [s]
6+
data_num_threshold: 200 # [num]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<?xml version="1.0" encoding="UTF-8"?>
2+
<launch>
3+
<arg name="input_imu_raw" default="imu_raw"/>
4+
<arg name="input_twist" default="twist"/>
5+
<arg name="output_gyro_bias" default="gyro_bias"/>
6+
<arg name="gyro_bias_estimator_param_file" default="$(find-pkg-share imu_corrector)/config/gyro_bias_estimator.param.yaml"/>
7+
<arg name="imu_corrector_param_file" default="$(find-pkg-share imu_corrector)/config/imu_corrector.param.yaml"/>
8+
9+
<node pkg="imu_corrector" exec="gyro_bias_estimator" name="gyro_bias_estimator" output="screen">
10+
<remap from="~/input/imu_raw" to="$(var input_imu_raw)"/>
11+
<remap from="~/input/twist" to="$(var input_twist)"/>
12+
<remap from="~/output/gyro_bias" to="$(var output_gyro_bias)"/>
13+
<param from="$(var gyro_bias_estimator_param_file)"/>
14+
<param from="$(var imu_corrector_param_file)"/>
15+
</node>
16+
</launch>

0 commit comments

Comments
 (0)