Skip to content

Commit

Permalink
feat: resource check (#1496)
Browse files Browse the repository at this point in the history
* 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]>
  • Loading branch information
12 people authored Aug 29, 2024
1 parent 07d0687 commit a5b62af
Show file tree
Hide file tree
Showing 34 changed files with 771 additions and 190 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ void ElevationMapLoaderNode::publish()
try {
is_bag_loaded = grid_map::GridMapRosConverter::loadFromBag(
*data_manager_.elevation_map_path_, "elevation_map", elevation_map_);
} catch (rosbag2_storage_plugins::SqliteException & e) {
} catch (const std::runtime_error & e) {
RCLCPP_ERROR(this->get_logger(), e.what());
is_bag_loaded = false;
}
if (!is_bag_loaded) {
Expand Down
23 changes: 0 additions & 23 deletions planning/behavior_path_planner/src/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,29 +26,6 @@
#include <string>
#include <vector>

namespace tier4_autoware_utils
{
template <class T>
double calcLateralOffset(
const T & points, const geometry_msgs::msg::Point & p_target, const size_t seg_idx)
{
validateNonEmpty(points);

const auto p_front = getPoint(points.at(seg_idx));
const auto p_back = getPoint(points.at(seg_idx + 1));

const Eigen::Vector3d segment_vec{p_back.x - p_front.x, p_back.y - p_front.y, 0.0};
const Eigen::Vector3d target_vec{p_target.x - p_front.x, p_target.y - p_front.y, 0.0};

if (segment_vec.norm() == 0.0) {
throw std::runtime_error("Same points are given.");
}

const Eigen::Vector3d cross_vec = segment_vec.cross(target_vec);
return cross_vec(2) / segment_vec.norm();
}
} // namespace tier4_autoware_utils

namespace drivable_area_utils
{
double quantize(const double val, const double resolution)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ class DetectionAreaModule : public SceneModuleInterface

public:
DetectionAreaModule(
const int64_t module_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem,
const int64_t module_id, const size_t lane_id,
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock);

Expand Down Expand Up @@ -106,6 +107,8 @@ class DetectionAreaModule : public SceneModuleInterface

// Debug
DebugData debug_data_;

int64_t lane_id_;
};
} // namespace behavior_velocity_planner

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,22 +28,24 @@ namespace behavior_velocity_planner
{
namespace
{
std::vector<lanelet::DetectionAreaConstPtr> getDetectionAreaRegElemsOnPath(
using DetectionAreaWithLaneId = std::pair<lanelet::DetectionAreaConstPtr, int64_t>;

std::vector<DetectionAreaWithLaneId> getDetectionAreaRegElemsOnPath(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const lanelet::LaneletMapPtr lanelet_map)
{
std::vector<lanelet::DetectionAreaConstPtr> detection_area_reg_elems;
std::vector<DetectionAreaWithLaneId> detection_areas_with_lane_id;

for (const auto & p : path.points) {
const auto lane_id = p.lane_ids.at(0);
const auto ll = lanelet_map->laneletLayer.get(lane_id);
const auto detection_areas = ll.regulatoryElementsAs<const lanelet::autoware::DetectionArea>();
for (const auto & detection_area : detection_areas) {
detection_area_reg_elems.push_back(detection_area);
detection_areas_with_lane_id.push_back(std::make_pair(detection_area, lane_id));
}
}

return detection_area_reg_elems;
return detection_areas_with_lane_id;
}

std::set<int64_t> getDetectionAreaIdSetOnPath(
Expand All @@ -52,7 +54,7 @@ std::set<int64_t> getDetectionAreaIdSetOnPath(
{
std::set<int64_t> detection_area_id_set;
for (const auto & detection_area : getDetectionAreaRegElemsOnPath(path, lanelet_map)) {
detection_area_id_set.insert(detection_area->id());
detection_area_id_set.insert(detection_area.first->id());
}
return detection_area_id_set;
}
Expand All @@ -72,14 +74,15 @@ DetectionAreaModuleManager::DetectionAreaModuleManager(rclcpp::Node & node)
void DetectionAreaModuleManager::launchNewModules(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path)
{
for (const auto & detection_area :
for (const auto & detection_area_with_lane_id :
getDetectionAreaRegElemsOnPath(path, planner_data_->route_handler_->getLaneletMapPtr())) {
// Use lanelet_id to unregister module when the route is changed
const auto module_id = detection_area->id();
const auto module_id = detection_area_with_lane_id.first->id();
const auto lane_id = detection_area_with_lane_id.second;
if (!isModuleRegistered(module_id)) {
registerModule(std::make_shared<DetectionAreaModule>(
module_id, *detection_area, planner_param_, logger_.get_child("detection_area_module"),
clock_));
module_id, lane_id, *(detection_area_with_lane_id.first), planner_param_,
logger_.get_child("detection_area_module"), clock_));
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,9 +69,13 @@ boost::optional<Point2d> getNearestCollisionPoint(
}

boost::optional<PathIndexWithPoint2d> findCollisionSegment(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line)
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line,
const SearchRangeIndex & search_index)
{
for (size_t i = 0; i < path.points.size() - 1; ++i) {
const auto min_search_index = std::max(static_cast<size_t>(0), search_index.min_idx);
const auto max_search_index = std::min(search_index.max_idx, path.points.size() - 1);

for (size_t i = min_search_index; i < max_search_index; ++i) {
const auto & p1 = path.points.at(i).point.pose.position; // Point before collision point
const auto & p2 = path.points.at(i + 1).point.pose.position; // Point after collision point

Expand Down Expand Up @@ -186,13 +190,15 @@ geometry_msgs::msg::Pose calcTargetPose(
} // namespace

DetectionAreaModule::DetectionAreaModule(
const int64_t module_id, const lanelet::autoware::DetectionArea & detection_area_reg_elem,
const int64_t module_id, const size_t lane_id,
const lanelet::autoware::DetectionArea & detection_area_reg_elem,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock),
detection_area_reg_elem_(detection_area_reg_elem),
state_(State::GO),
planner_param_(planner_param)
planner_param_(planner_param),
lane_id_(lane_id)
{
}

Expand Down Expand Up @@ -351,8 +357,13 @@ bool DetectionAreaModule::isOverLine(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const geometry_msgs::msg::Pose & self_pose, const geometry_msgs::msg::Pose & line_pose) const
{
return tier4_autoware_utils::calcSignedArcLength(
path.points, self_pose.position, line_pose.position) < 0;
const PointWithSearchRangeIndex src_point_with_search_range_index =
planning_utils::findFirstNearSearchRangeIndex(path.points, self_pose.position);
const PointWithSearchRangeIndex dst_point_with_search_range_index = {
line_pose.position, planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_)};

return planning_utils::calcSignedArcLengthWithSearchIndex(
path.points, src_point_with_search_range_index, dst_point_with_search_range_index) < 0;
}

bool DetectionAreaModule::hasEnoughBrakingDistance(
Expand Down Expand Up @@ -392,8 +403,10 @@ boost::optional<PathIndexWithPose> DetectionAreaModule::createTargetPoint(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const LineString2d & stop_line,
const double margin) const
{
const auto dst_search_range = planning_utils::getPathIndexRangeIncludeLaneId(path, lane_id_);

// Find collision segment
const auto collision_segment = findCollisionSegment(path, stop_line);
const auto collision_segment = findCollisionSegment(path, stop_line, dst_search_range);
if (!collision_segment) {
// No collision
return {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,10 @@ template <typename T>
boost::optional<geometry_msgs::msg::Pose> lerpPose(
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
{
if (points.size() < 2) {
return {};
}

constexpr double epsilon = 1e-6;

const double closest_to_target_dist =
Expand Down Expand Up @@ -94,6 +98,10 @@ template <typename T>
double lerpTwistX(
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
{
if (points.size() < 2) {
return 0.0;
}

constexpr double epsilon = 1e-6;

const double closest_to_target_dist =
Expand All @@ -116,6 +124,10 @@ template <typename T>
double lerpPoseZ(
const T & points, const geometry_msgs::msg::Point & target_pos, const size_t closest_seg_idx)
{
if (points.size() < 2) {
return 0.0;
}

constexpr double epsilon = 1e-6;

const double closest_to_target_dist =
Expand Down
3 changes: 3 additions & 0 deletions planning/obstacle_avoidance_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1093,6 +1093,9 @@ void ObstacleAvoidancePlanner::calcVelocity(
const std::vector<autoware_auto_planning_msgs::msg::PathPoint> & path_points,
std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & traj_points) const
{
if (path_points.size() < 2) {
return;
}
for (size_t i = 0; i < traj_points.size(); i++) {
const size_t nearest_seg_idx = [&]() {
const auto opt_seg_idx = tier4_autoware_utils::findNearestSegmentIndex(
Expand Down
4 changes: 4 additions & 0 deletions planning/obstacle_stop_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -753,6 +753,10 @@ void ObstacleStopPlannerNode::insertVelocity(
const std_msgs::msg::Header & trajectory_header, const VehicleInfo & vehicle_info,
const double current_acc, const double current_vel, const StopParam & stop_param)
{
if (output.size() < 3) {
return;
}

if (planner_data.stop_require) {
// insert stop point
const auto traj_end_idx = output.size() - 1;
Expand Down
2 changes: 1 addition & 1 deletion planning/planning_error_monitor/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ This function checks if the relative angle at point1 generated from point2 and 3
| :------------------------ | :------- | :------------------------------------ | :------------ |
| `error_interval` | `double` | Error Interval Distance Threshold [m] | 100.0 |
| `error_curvature` | `double` | Error Curvature Threshold | 1.0 |
| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | $\pi$/4 |
| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | 2.0 |
| `ignore_too_close_points` | `double` | Ignore Too Close Distance Threshold | 0.005 |

## Visualization
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
<remap from="~/input/trajectory" to="$(var input/trajectory)"/>
<param name="error_interval" value="100.0"/>
<param name="error_curvature" value="2.0"/>
<param name="error_sharp_angle" value="0.785398"/>
<param name="error_sharp_angle" value="2.0"/>
<param name="ignore_too_close_points" value="0.01"/>
</node>
</launch>
2 changes: 1 addition & 1 deletion planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path)
continue;
}

constexpr double min_dist = 0.001;
constexpr double min_dist = 0.1;
if (
tier4_autoware_utils::calcDistance3d(filtered_path.points.back().point, pt.point) <
min_dist) {
Expand Down
25 changes: 24 additions & 1 deletion sensing/imu_corrector/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,42 @@ endif()
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_add_library(gyro_bias_estimation_module SHARED
src/gyro_bias_estimation_module.cpp
)

ament_auto_add_library(imu_corrector_node SHARED
src/imu_corrector_core.cpp
include/imu_corrector/imu_corrector_core.hpp
)

ament_auto_add_library(gyro_bias_estimator_node SHARED
src/gyro_bias_estimator.cpp
)

target_link_libraries(gyro_bias_estimator_node gyro_bias_estimation_module)

rclcpp_components_register_node(imu_corrector_node
PLUGIN "imu_corrector::ImuCorrector"
EXECUTABLE imu_corrector
)

rclcpp_components_register_node(gyro_bias_estimator_node
PLUGIN "imu_corrector::GyroBiasEstimator"
EXECUTABLE gyro_bias_estimator
)

function(add_testcase filepath)
get_filename_component(filename ${filepath} NAME)
string(REGEX REPLACE ".cpp" "" test_name ${filename})
ament_add_gmock(${test_name} ${filepath})
target_link_libraries("${test_name}" gyro_bias_estimation_module imu_corrector_node gyro_bias_estimator_node)
ament_target_dependencies(${test_name} ${${PROJECT_NAME}_FOUND_BUILD_DEPENDS})
endfunction()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
add_testcase(test/test_gyro_bias_estimation_module.cpp)
endif()

ament_auto_package(INSTALL_TO_SHARE
Expand Down
39 changes: 28 additions & 11 deletions sensing/imu_corrector/README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# imu_corrector

## Purpose
## imu_corrector

`imu_corrector_node` is a node that correct imu data.

Expand All @@ -10,8 +10,6 @@
<!-- TODO(TIER IV): Make this repository public or change the link. -->
<!-- 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. -->

## Inputs / Outputs

### Input

| Name | Type | Description |
Expand All @@ -24,9 +22,7 @@
| --------- | ----------------------- | ------------------ |
| `~output` | `sensor_msgs::msg::Imu` | corrected imu data |

## Parameters

### Core Parameters
### Parameters

| Name | Type | Description |
| ---------------------------- | ------ | ------------------------------------- |
Expand All @@ -37,12 +33,33 @@
| `angular_velocity_stddev_yy` | double | pitch rate standard deviation [rad/s] |
| `angular_velocity_stddev_zz` | double | yaw rate standard deviation [rad/s] |

## Assumptions / Known limits
## gyro_bias_estimator

`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.

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

## (Optional) Performance characterization
### Input

| Name | Type | Description |
| ----------------- | ------------------------------------------------ | ---------------- |
| `~/input/imu_raw` | `sensor_msgs::msg::Imu` | **raw** imu data |
| `~/input/twist` | `geometry_msgs::msg::TwistWithCovarianceStamped` | vehicle velocity |

## (Optional) References/External links
### Output

## (Optional) Future extensions / Unimplemented parts
| Name | Type | Description |
| -------------------- | ------------------------------------ | ----------------------------- |
| `~/output/gyro_bias` | `geometry_msgs::msg::Vector3Stamped` | bias of the gyroscope [rad/s] |

### Parameters

| Name | Type | Description |
| --------------------------- | ------ | ----------------------------------------------------------------------------- |
| `angular_velocity_offset_x` | double | roll rate offset in imu_link [rad/s] |
| `angular_velocity_offset_y` | double | pitch rate offset imu_link [rad/s] |
| `angular_velocity_offset_z` | double | yaw rate offset imu_link [rad/s] |
| `gyro_bias_threshold` | double | threshold of the bias of the gyroscope [rad/s] |
| `velocity_threshold` | double | threshold of the vehicle velocity to determine if the vehicle is stopped[m/s] |
| `timestamp_threshold` | double | threshold of the timestamp diff between IMU and twist [s] |
| `data_num_threshold` | int | number of data used to calculate bias |
6 changes: 6 additions & 0 deletions sensing/imu_corrector/config/gyro_bias_estimator.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
gyro_bias_threshold: 0.0015 # [rad/s]
velocity_threshold: 0.0 # [m/s]
timestamp_threshold: 0.1 # [s]
data_num_threshold: 200 # [num]
16 changes: 16 additions & 0 deletions sensing/imu_corrector/launch/gyro_bias_estimator.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="input_imu_raw" default="imu_raw"/>
<arg name="input_twist" default="twist"/>
<arg name="output_gyro_bias" default="gyro_bias"/>
<arg name="gyro_bias_estimator_param_file" default="$(find-pkg-share imu_corrector)/config/gyro_bias_estimator.param.yaml"/>
<arg name="imu_corrector_param_file" default="$(find-pkg-share imu_corrector)/config/imu_corrector.param.yaml"/>

<node pkg="imu_corrector" exec="gyro_bias_estimator" name="gyro_bias_estimator" output="screen">
<remap from="~/input/imu_raw" to="$(var input_imu_raw)"/>
<remap from="~/input/twist" to="$(var input_twist)"/>
<remap from="~/output/gyro_bias" to="$(var output_gyro_bias)"/>
<param from="$(var gyro_bias_estimator_param_file)"/>
<param from="$(var imu_corrector_param_file)"/>
</node>
</launch>
Loading

0 comments on commit a5b62af

Please sign in to comment.