Skip to content

Commit

Permalink
feat!: remove planning factor type (autowarefoundation#5793)
Browse files Browse the repository at this point in the history
remove planning factor type

Signed-off-by: Takagi, Isamu <[email protected]>
Co-authored-by: Hiroki OTA <[email protected]>
  • Loading branch information
2 people authored and karishma1911 committed May 28, 2024
1 parent 1411031 commit 8911278
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 96 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -174,9 +174,6 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray::
case SteeringFactor::APPROACHING:
label->setText("APPROACHING");
break;
case SteeringFactor::TRYING:
label->setText("TRYING");
break;
case SteeringFactor::TURNING:
label->setText("TURNING");
break;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -490,16 +490,10 @@ void BehaviorPathPlannerNode::publish_steering_factor(

const auto [intersection_pose, intersection_distance] =
planner_data->turn_signal_decider.getIntersectionPoseAndDistance();
const uint16_t steering_factor_state = std::invoke([&intersection_flag]() {
if (intersection_flag) {
return SteeringFactor::TURNING;
}
return SteeringFactor::TRYING;
});

steering_factor_interface_ptr_->updateSteeringFactor(
{intersection_pose, intersection_pose}, {intersection_distance, intersection_distance},
PlanningBehavior::INTERSECTION, steering_factor_direction, steering_factor_state, "");
PlanningBehavior::INTERSECTION, steering_factor_direction, SteeringFactor::TURNING, "");
} else {
steering_factor_interface_ptr_->clearSteeringFactors();
}
Expand Down
86 changes: 0 additions & 86 deletions system/default_ad_api/src/planning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,82 +63,6 @@ T merge_factors(const rclcpp::Time stamp, const std::vector<typename T::ConstSha
return message;
}

uint16_t convert_velocity_behavior(const std::string & behavior)
{
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::VelocityFactor;

if (behavior == PlanningBehavior::AVOIDANCE) {
return VelocityFactor::AVOIDANCE;
}
if (behavior == PlanningBehavior::CROSSWALK) {
return VelocityFactor::CROSSWALK;
}
if (behavior == PlanningBehavior::INTERSECTION) {
return VelocityFactor::INTERSECTION;
}
if (behavior == PlanningBehavior::LANE_CHANGE) {
return VelocityFactor::LANE_CHANGE;
}
if (behavior == PlanningBehavior::MERGE) {
return VelocityFactor::MERGE;
}
if (behavior == PlanningBehavior::NO_DRIVABLE_LANE) {
return VelocityFactor::NO_DRIVABLE_LANE;
}
if (behavior == PlanningBehavior::NO_STOPPING_AREA) {
return VelocityFactor::NO_STOPPING_AREA;
}
if (behavior == PlanningBehavior::REAR_CHECK) {
return VelocityFactor::REAR_CHECK;
}
if (behavior == PlanningBehavior::ROUTE_OBSTACLE) {
return VelocityFactor::ROUTE_OBSTACLE;
}
if (behavior == PlanningBehavior::SIDEWALK) {
return VelocityFactor::SIDEWALK;
}
if (behavior == PlanningBehavior::STOP_SIGN) {
return VelocityFactor::STOP_SIGN;
}
if (behavior == PlanningBehavior::SURROUNDING_OBSTACLE) {
return VelocityFactor::SURROUNDING_OBSTACLE;
}
if (behavior == PlanningBehavior::TRAFFIC_SIGNAL) {
return VelocityFactor::TRAFFIC_SIGNAL;
}
if (behavior == PlanningBehavior::USER_DEFINED_DETECTION_AREA) {
return VelocityFactor::USER_DEFINED_DETECTION_AREA;
}
if (behavior == PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT) {
return VelocityFactor::V2I_GATE_CONTROL_ENTER;
}
return VelocityFactor::UNKNOWN;
}

uint16_t convert_steering_behavior(const std::string & behavior)
{
using autoware_adapi_v1_msgs::msg::PlanningBehavior;
using autoware_adapi_v1_msgs::msg::SteeringFactor;

if (behavior == PlanningBehavior::AVOIDANCE) {
return SteeringFactor::AVOIDANCE_PATH_CHANGE;
}
if (behavior == PlanningBehavior::GOAL_PLANNER) {
return SteeringFactor::GOAL_PLANNER;
}
if (behavior == PlanningBehavior::INTERSECTION) {
return SteeringFactor::INTERSECTION;
}
if (behavior == PlanningBehavior::LANE_CHANGE) {
return SteeringFactor::LANE_CHANGE;
}
if (behavior == PlanningBehavior::START_PLANNER) {
return SteeringFactor::START_PLANNER;
}
return SteeringFactor::UNKNOWN;
}

PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning", options)
{
// TODO(Takagi, Isamu): remove default value
Expand Down Expand Up @@ -203,16 +127,6 @@ void PlanningNode::on_timer()
auto velocity = merge_factors<VelocityFactorArray>(now(), velocity_factors_);
auto steering = merge_factors<SteeringFactorArray>(now(), steering_factors_);

// Set velocity factor type for compatibility.
for (auto & factor : velocity.factors) {
factor.type = convert_velocity_behavior(factor.behavior);
}

// Set steering factor type for compatibility.
for (auto & factor : steering.factors) {
factor.type = convert_steering_behavior(factor.behavior);
}

// Set the distance if it is nan.
if (trajectory_ && kinematic_state_) {
for (auto & factor : velocity.factors) {
Expand Down

0 comments on commit 8911278

Please sign in to comment.