Skip to content

Commit

Permalink
fix pre-commit and move updateRTCStatus to cpp file
Browse files Browse the repository at this point in the history
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed May 1, 2023
1 parent 609b2c0 commit 7ac9f85
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -129,16 +129,7 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface
ModuleStatus updateState() override;

protected:
void updateRTCStatus(const double start_distance, const double finish_distance) override
{
const auto direction = std::invoke([&]() -> std::string {
const auto dir = module_type_->getDirection();
return (dir == Direction::LEFT) ? "left" : "right";
});

rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
}
void updateRTCStatus(const double start_distance, const double finish_distance) override;
};

class LaneChangeBTInterface : public LaneChangeInterface
Expand Down Expand Up @@ -178,16 +169,7 @@ class LaneChangeBTModule : public LaneChangeBTInterface
const std::shared_ptr<LaneChangeParameters> & parameters);

protected:
void updateRTCStatus(const double start_distance, const double finish_distance) override
{
const auto direction = std::invoke([&]() -> std::string {
const auto dir = module_type_->getDirection();
return (dir == Direction::LEFT) ? "left" : "right";
});

rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
}
void updateRTCStatus(const double start_distance, const double finish_distance) override;
};

class ExternalRequestLaneChangeLeftBTModule : public LaneChangeBTInterface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -356,6 +356,18 @@ ModuleStatus AvoidanceByLaneChangeInterface::updateState()
return current_state_;
}

void AvoidanceByLaneChangeInterface::updateRTCStatus(
const double start_distance, const double finish_distance)
{
const auto direction = std::invoke([&]() -> std::string {
const auto dir = module_type_->getDirection();
return (dir == Direction::LEFT) ? "left" : "right";
});

rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
}

LaneChangeBTInterface::LaneChangeBTInterface(
const std::string & name, rclcpp::Node & node,
const std::shared_ptr<LaneChangeParameters> & parameters,
Expand Down Expand Up @@ -460,6 +472,18 @@ LaneChangeBTModule::LaneChangeBTModule(
std::make_unique<NormalLaneChangeBT>(parameters, LaneChangeModuleType::NORMAL, Direction::NONE)}
{
}

void LaneChangeBTModule::updateRTCStatus(const double start_distance, const double finish_distance)
{
const auto direction = std::invoke([&]() -> std::string {
const auto dir = module_type_->getDirection();
return (dir == Direction::LEFT) ? "left" : "right";
});

rtc_interface_ptr_map_.at(direction)->updateCooperateStatus(
uuid_map_.at(direction), isExecutionReady(), start_distance, finish_distance, clock_->now());
}

ExternalRequestLaneChangeLeftBTModule::ExternalRequestLaneChangeLeftBTModule(
const std::string & name, rclcpp::Node & node,
const std::shared_ptr<LaneChangeParameters> & parameters)
Expand Down

0 comments on commit 7ac9f85

Please sign in to comment.