Skip to content

Commit

Permalink
chore(behavior_velocity): fix spell check
Browse files Browse the repository at this point in the history
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
  • Loading branch information
taikitanaka3 committed Mar 15, 2022
1 parent 355f37a commit aea0b3d
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ namespace occlusion_spot_utils
{
enum ROAD_TYPE { PRIVATE, PUBLIC, HIGHWAY, UNKNOWN };
enum DETECTION_METHOD { OCCUPANCY_GRID, PREDICTED_OBJECT };
enum PASS_JUDGE { SMOOTH_VELOCITY, CURRENT_VELCITY };
enum PASS_JUDGE { SMOOTH_VELOCITY, CURRENT_VELOCITY };

struct DetectionArea
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ OcclusionSpotModuleManager::OcclusionSpotModuleManager(rclcpp::Node & node)
{
const std::string pass_judge = node.declare_parameter(ns + ".pass_judge", "current_velocity");
if (pass_judge == "current_velocity") {
pp.pass_judge = PASS_JUDGE::CURRENT_VELCITY;
pp.pass_judge = PASS_JUDGE::CURRENT_VELOCITY;
} else {
throw std::invalid_argument{
"[behavior_velocity]: occlusion spot pass judge method has invalid argument"};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ bool OcclusionSpotModule::modifyPathVelocity(
//! never change this interpolation interval(will affect module accuracy)
splineInterpolate(clipped_path, 1.0, &interp_path, logger_);
debug_data_.interp_path = interp_path;
if (param_.pass_judge == utils::PASS_JUDGE::CURRENT_VELCITY) {
if (param_.pass_judge == utils::PASS_JUDGE::CURRENT_VELOCITY) {
interp_path = utils::applyVelocityToPath(interp_path, param_.v.v_ego);
} else if (param_.pass_judge == utils::PASS_JUDGE::SMOOTH_VELOCITY) {
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include <scene_module/occlusion_spot/risk_predictive_braking.hpp>
#include <scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.hpp>
#include <utilization/path_utilization.hpp>
#include <utilization/trajectory_utils.hpp>
#include <utilization/util.hpp>

#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
Expand Down Expand Up @@ -73,9 +74,12 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity(
utils::clipPathByLength(*path, clipped_path, param_.detection_area_length);
PathWithLaneId interp_path;
splineInterpolate(clipped_path, 1.0, &interp_path, logger_);
if (param_.pass_judge == utils::PASS_JUDGE::CURRENT_VELCITY) {
if (param_.pass_judge == utils::PASS_JUDGE::CURRENT_VELOCITY) {
interp_path = utils::applyVelocityToPath(interp_path, param_.v.v_ego);
} else if (param_.pass_judge == utils::PASS_JUDGE::SMOOTH_VELOCITY) {
if (!smoothPath(interp_path, interp_path, planner_data_)) {
// use max velocity in path if optimization failure
}
}
const geometry_msgs::msg::Point start_point = interp_path.points.at(0).point.pose.position;
const auto offset = tier4_autoware_utils::calcSignedArcLength(
Expand Down

0 comments on commit aea0b3d

Please sign in to comment.