Skip to content

Commit

Permalink
Merge branch 'beta/v0.3.19' into feat/apply_mrm_by_pose_instability_risk
Browse files Browse the repository at this point in the history
  • Loading branch information
yn-mrse authored Oct 1, 2024
2 parents 17d1a5b + 0245366 commit c09e4e1
Show file tree
Hide file tree
Showing 6 changed files with 16 additions and 1 deletion.
5 changes: 5 additions & 0 deletions control/lane_departure_checker/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,10 @@ This package includes the following features:

2. Expand footprint based on the standard deviation multiplied with `footprint_margin_scale`.

### How to extend footprint by constant

Expand footprint based on the constant defined with `footprint_extra_margin`.

## Interface

### Input
Expand Down Expand Up @@ -72,6 +76,7 @@ This package includes the following features:
| Name | Type | Description | Default value |
| :------------------------- | :----- | :--------------------------------------------------------------------------------- | :------------ |
| footprint_margin_scale | double | Coefficient for expanding footprint margin. Multiplied by 1 standard deviation. | 1.0 |
| footprint_extra_margin | double | Coefficient for expanding footprint margin. When checking for lane departure.[m] | 0.0 |
| resample_interval | double | Minimum Euclidean distance between points when resample trajectory.[m] | 0.3 |
| max_deceleration | double | Maximum deceleration when calculating braking distance. | 2.8 |
| delay_time | double | Delay time which took to actuate brake when calculating braking distance. [second] | 1.3 |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

# Core
footprint_margin_scale: 1.0
footprint_extra_margin: 0.0
resample_interval: 0.3
max_deceleration: 2.8
delay_time: 1.3
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ using TrajectoryPoints = std::vector<TrajectoryPoint>;
struct Param
{
double footprint_margin_scale;
double footprint_extra_margin;
double resample_interval;
double max_deceleration;
double delay_time;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,4 +89,9 @@ inline FootprintMargin calcFootprintMargin(
return FootprintMargin{Cov_xy_vehicle(0, 0) * scale, Cov_xy_vehicle(1, 1) * scale};
}

inline FootprintMargin operator+(FootprintMargin fm, const double margin)
{
return FootprintMargin{fm.lon + margin, fm.lat + margin};
}

#endif // LANE_DEPARTURE_CHECKER__UTIL__CREATE_VEHICLE_FOOTPRINT_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,8 @@ std::vector<LinearRing2d> LaneDepartureChecker::createVehicleFootprints(
const Param & param)
{
// Calculate longitudinal and lateral margin based on covariance
const auto margin = calcFootprintMargin(covariance, param.footprint_margin_scale);
const auto margin =
calcFootprintMargin(covariance, param.footprint_margin_scale) + param.footprint_extra_margin;

// Create vehicle footprint in base_link coordinate
const auto local_vehicle_footprint = createVehicleFootprint(*vehicle_info_ptr_, margin);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ LaneDepartureCheckerNode::LaneDepartureCheckerNode(const rclcpp::NodeOptions & o
vehicle_length_m_ = vehicle_info.vehicle_length_m;

param_.footprint_margin_scale = declare_parameter("footprint_margin_scale", 1.0);
param_.footprint_extra_margin = declare_parameter("footprint_extra_margin", 0.0);
param_.resample_interval = declare_parameter("resample_interval", 0.3);
param_.max_deceleration = declare_parameter("max_deceleration", 3.0);
param_.delay_time = declare_parameter("delay_time", 0.3);
Expand Down Expand Up @@ -352,6 +353,7 @@ rcl_interfaces::msg::SetParametersResult LaneDepartureCheckerNode::onParameter(

// Core
update_param(parameters, "footprint_margin_scale", param_.footprint_margin_scale);
update_param(parameters, "footprint_extra_margin", param_.footprint_extra_margin);
update_param(parameters, "resample_interval", param_.resample_interval);
update_param(parameters, "max_deceleration", param_.max_deceleration);
update_param(parameters, "delay_time", param_.delay_time);
Expand Down

0 comments on commit c09e4e1

Please sign in to comment.