Skip to content

Commit

Permalink
ビルドエラー修正
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Dec 1, 2024
1 parent 22f04b6 commit a637e44
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class AttackerSkillPlanner : public PlannerBase
skill = std::make_shared<skills::Attacker>(base);
return {our_frontier->robot->id};
} else {
return
return {};
}
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,26 +32,24 @@ class OffensivePlanner : public PlannerBase
public:
std::shared_ptr<skills::Attacker> attacker = nullptr;

COMPOSITION_PUBLIC explicit OffensivePlanner(
WorldModelWrapper::SharedPtr & world_model,
const ConsaiVisualizerWrapper::SharedPtr & visualizer)
: PlannerBase("Offensive", world_model, visualizer)
COMPOSITION_PUBLIC explicit OffensivePlanner(WorldModelWrapper::SharedPtr & world_model)
: PlannerBase("Offensive", world_model)
{
}

std::pair<Status, std::vector<crane_msgs::msg::RobotCommand>> calculateRobotCommand(
const std::vector<RobotIdentifier> & robots, PlannerContext & context) override
{
std::string state_name(magic_enum::enum_name(skill->getCurrentState()));
std::string state_name(magic_enum::enum_name(attacker->getCurrentState()));
visualizer->addCircle(
skill->commander().getRobot()->pose.pos, 0.3, 2, "red", "", 1.0, state_name);
attacker->commander().getRobot()->pose.pos, 0.3, 2, "red", "", 1.0, state_name);
visualizer->addLine(
world_model->ball.pos,
world_model->ball.pos +
world_model->ball.vel.normalized() * world_model->getBallDistanceHorizon(),
3, "red", 0.5, "");
auto status = skill->run(visualizer);
return {static_cast<PlannerBase::Status>(status), {skill->getRobotCommand()}};
auto status = attacker->run();
return {static_cast<PlannerBase::Status>(status), {attacker->getRobotCommand()}};
}

auto getSelectedRobots(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,8 @@ class PassReceiverPlanner : public PlannerBase

Point pass_target;

COMPOSITION_PUBLIC explicit PassReceiverPlanner(
WorldModelWrapper::SharedPtr & world_model,
const ConsaiVisualizerWrapper::SharedPtr & visualizer)
: PlannerBase("PassReceiver", world_model, visualizer)
COMPOSITION_PUBLIC explicit PassReceiverPlanner(WorldModelWrapper::SharedPtr & world_model)
: PlannerBase("PassReceiver", world_model)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ void SessionControllerComponent::request(
const std::unordered_map<uint8_t, RobotRole> & prev_roles = *PlannerBase::robot_roles;
auto [response, new_planner] = [&]() {
auto planner = generatePlanner(p.session_name, world_model);
auto response = planner->doRobotSelect(req, prev_roles);
auto response = planner->doRobotSelect(req, prev_roles, planner_context);
return std::make_pair(response, planner);
}();

Expand Down

0 comments on commit a637e44

Please sign in to comment.