Skip to content

Commit

Permalink
お掃除(すっきり〜)
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Feb 21, 2024
1 parent acf79d1 commit 277f4d0
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 27 deletions.
1 change: 0 additions & 1 deletion crane_simple_ai/include/crane_commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,6 @@ class ROSNode : public rclcpp::Node
ROSNode() : Node("crane_commander")
{
world_model = std::make_shared<crane::WorldModelWrapper>(*this);
commander = std::make_shared<crane::RobotCommandWrapper>(0, world_model);
visualizer = std::make_shared<crane::ConsaiVisualizerWrapper>(*this, "simple_ai");
publisher_robot_commands =
create_publisher<crane_msgs::msg::RobotCommands>("/control_targets", 10);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,12 +86,9 @@ class MarkerPlanner : public PlannerBase
selected_robots.push_back(selectable_robots[min_index]);
skill_map.emplace(
selectable_robots[min_index],
std::make_pair(
std::make_shared<RobotCommandWrapper>(selectable_robots[min_index], world_model),
std::make_shared<skills::Marker>(selectable_robots[min_index], world_model)));
skill_map[selectable_robots[min_index]].second->setParameter(
"marking_robot_id", enemy_robot->id);
skill_map[selectable_robots[min_index]].second->setParameter("mark_distance", 0.5);
std::make_shared<skills::Marker>(selectable_robots[min_index], world_model));
skill_map[selectable_robots[min_index]]->setParameter("marking_robot_id", enemy_robot->id);
skill_map[selectable_robots[min_index]]->setParameter("mark_distance", 0.5);
}

return selected_robots;
Expand All @@ -101,9 +98,7 @@ class MarkerPlanner : public PlannerBase
// key: ID of our robot in charge, value: ID of the enemy marked robot
std::unordered_map<uint8_t, uint8_t> marking_target_map;

std::unordered_map<
uint8_t, std::pair<std::shared_ptr<RobotCommandWrapper>, std::shared_ptr<skills::Marker>>>
skill_map;
std::unordered_map<uint8_t, std::shared_ptr<skills::Marker>> skill_map;
};

} // namespace crane
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,8 @@ class OurKickOffPlanner : public PlannerBase
private:
std::shared_ptr<skills::KickoffAttack> kickoff_attack;

std::shared_ptr<RobotCommandWrapper> attacker_command;

std::shared_ptr<skills::KickoffSupport> kickoff_support;

std::shared_ptr<RobotCommandWrapper> supporter_command;

public:
COMPOSITION_PUBLIC explicit OurKickOffPlanner(
WorldModelWrapper::SharedPtr & world_model, ConsaiVisualizerWrapper::SharedPtr visualizer)
Expand Down Expand Up @@ -83,9 +79,7 @@ class OurKickOffPlanner : public PlannerBase
});

kickoff_attack = std::make_shared<skills::KickoffAttack>(*best_attacker, world_model);
attacker_command = std::make_shared<RobotCommandWrapper>(*best_attacker, world_model);
kickoff_support = std::make_shared<skills::KickoffSupport>(*best_supporter, world_model);
supporter_command = std::make_shared<RobotCommandWrapper>(*best_supporter, world_model);

return {*best_attacker, *best_supporter};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,6 @@ class GoalieSkillPlanner : public PlannerBase
public:
std ::shared_ptr<skills::Goalie> skill = nullptr;

std ::shared_ptr<RobotCommandWrapper> robot_command_wrapper = nullptr;

COMPOSITION_PUBLIC explicit GoalieSkillPlanner(
WorldModelWrapper ::SharedPtr & world_model, ConsaiVisualizerWrapper ::SharedPtr visualizer)
: PlannerBase("Goalie", world_model, visualizer)
Expand All @@ -76,7 +74,7 @@ class GoalieSkillPlanner : public PlannerBase
std ::pair<Status, std ::vector<crane_msgs ::msg ::RobotCommand>> calculateRobotCommand(
const std ::vector<RobotIdentifier> & robots) override
{
if (not skill or not robot_command_wrapper) {
if (not skill) {
return {PlannerBase ::Status ::RUNNING, {}};
} else {
std ::vector<crane_msgs ::msg ::RobotCommand> robot_commands;
Expand All @@ -89,8 +87,6 @@ class GoalieSkillPlanner : public PlannerBase
-> std ::vector<uint8_t> override
{
skill = std ::make_shared<skills ::Goalie>(world_model->getOurGoalieId(), world_model);
robot_command_wrapper =
std ::make_shared<RobotCommandWrapper>(world_model->getOurGoalieId(), world_model);
return {world_model->getOurGoalieId()};
}
};
Expand All @@ -100,8 +96,6 @@ class BallPlacementSkillPlanner : public PlannerBase
public:
std ::shared_ptr<skills::SingleBallPlacement> skill = nullptr;

std ::shared_ptr<RobotCommandWrapper> robot_command_wrapper = nullptr;

COMPOSITION_PUBLIC explicit BallPlacementSkillPlanner(
WorldModelWrapper ::SharedPtr & world_model, ConsaiVisualizerWrapper ::SharedPtr visualizer)
: PlannerBase("BallPlacement", world_model, visualizer)
Expand All @@ -111,7 +105,7 @@ class BallPlacementSkillPlanner : public PlannerBase
std ::pair<Status, std ::vector<crane_msgs ::msg ::RobotCommand>> calculateRobotCommand(
const std ::vector<RobotIdentifier> & robots) override
{
if (not skill or not robot_command_wrapper) {
if (not skill) {
return {PlannerBase ::Status ::RUNNING, {}};
} else {
if (auto target = world_model->getBallPlacementTarget(); target.has_value()) {
Expand Down Expand Up @@ -140,9 +134,6 @@ class BallPlacementSkillPlanner : public PlannerBase
skill->setParameter("placement_x", target->x());
skill->setParameter("placement_y", target->y());
}

robot_command_wrapper =
std ::make_shared<RobotCommandWrapper>(selected_robots.front(), world_model);
return {selected_robots.front()};
}
};
Expand Down

0 comments on commit 277f4d0

Please sign in to comment.