diff --git a/crane_msgs/msg/analysis/PlaySituation.msg b/crane_msgs/msg/analysis/PlaySituation.msg index 8e027314c..02f767930 100755 --- a/crane_msgs/msg/analysis/PlaySituation.msg +++ b/crane_msgs/msg/analysis/PlaySituation.msg @@ -32,7 +32,7 @@ uint8 OUR_PENALTY_PREPARATION = 13 uint8 OUR_PENALTY_START = 14 uint8 OUR_DIRECT_FREE = 15 # uint8 OUR_INDIRECT_FREE = 16 現在は非推奨(使われていない) -# uint8 OUR_TIMEOUT = 17 use halt +uint8 OUR_TIMEOUT = 17 # uint8 OUR_GOAL = 18 use halt uint8 OUR_BALL_PLACEMENT = 19 @@ -42,7 +42,7 @@ uint8 THEIR_PENALTY_PREPARATION = 23 uint8 THEIR_PENALTY_START = 24 uint8 THEIR_DIRECT_FREE = 25 # uint8 THEIR_INDIRECT_FREE = 26 現在は非推奨(使われていない) -# uint8 THEIR_TIMEOUT = 27 use halt +uint8 THEIR_TIMEOUT = 27 # uint8 THEIR_GOAL = 28 use halt uint8 THEIR_BALL_PLACEMENT = 29 diff --git a/crane_play_switcher/src/play_switcher.cpp b/crane_play_switcher/src/play_switcher.cpp index bc4d4d113..d5dc6e9e0 100644 --- a/crane_play_switcher/src/play_switcher.cpp +++ b/crane_play_switcher/src/play_switcher.cpp @@ -150,13 +150,14 @@ void PlaySwitcher::referee_callback(const robocup_ssl_msgs::msg::Referee & msg) command_map[Referee::COMMAND_HALT] = PlaySituation::HALT; command_map[Referee::COMMAND_STOP] = PlaySituation::STOP; - REDIRECT_MAPPING(TIMEOUT, HALT) + // REDIRECT_MAPPING(TIMEOUT, HALT) REDIRECT_MAPPING(GOAL, HALT) CMD_MAPPING(is_yellow, PREPARE_KICKOFF, KICKOFF_PREPARATION) CMD_MAPPING(is_yellow, PREPARE_PENALTY, PENALTY_PREPARATION) CMD_MAPPING(is_yellow, DIRECT_FREE, DIRECT_FREE) CMD_MAPPING(is_yellow, BALL_PLACEMENT, BALL_PLACEMENT) + CMD_MAPPING(is_yellow, TIMEOUT, TIMEOUT) next_play_situation = command_map[msg.command]; inplay_command_info.reason = "RAWコマンド変化:コマンド転送"; diff --git a/crane_robot_skills/src/attacker.cpp b/crane_robot_skills/src/attacker.cpp index d564a7a0e..e1ffe9700 100644 --- a/crane_robot_skills/src/attacker.cpp +++ b/crane_robot_skills/src/attacker.cpp @@ -29,13 +29,16 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base) if ( game_command == crane_msgs::msg::PlaySituation::OUR_DIRECT_FREE || game_command == crane_msgs::msg::PlaySituation::OUR_KICKOFF_START) { - auto best_receiver = selectPassReceiver(); - forced_pass_receiver_id = best_receiver->id; - setParameter("receiver_id", best_receiver->id); - auto receiver = world_model()->getOurRobot(forced_pass_receiver_id); - kick_skill.setParameter("target", receiver->pose.pos); - forced_pass_phase = 1; - return true; + if (auto best_receiver = selectPassReceiver(); best_receiver) { + forced_pass_receiver_id = best_receiver->id; + setParameter("receiver_id", best_receiver->id); + auto receiver = world_model()->getOurRobot(forced_pass_receiver_id); + kick_skill.setParameter("target", receiver->pose.pos); + forced_pass_phase = 1; + return true; + } else { + return false; + } } else { return false; } @@ -62,6 +65,7 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base) if (receiver_id != -1) { kick_target = world_model()->getOurRobot(receiver_id)->pose.pos; } + kick_skill.setParameter("target", kick_target); Segment kick_line{world_model()->ball.pos, kick_target}; // 近くに敵ロボットがいればチップキック if (const auto enemy_robots = world_model()->theirs.getAvailableRobots(); @@ -376,7 +380,7 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base) addStateFunction(AttackerState::KICK_TO_GOAL, [this]() -> Status { kick_skill.setParameter("target", world_model()->getTheirGoalCenter()); - kick_skill.setParameter("kick_power", 0.8); + kick_skill.setParameter("kick_power", 0.9); // kick_skill.setParameter("dot_threshold", 0.95); kick_skill.setParameter("kick_with_chip", false); return kick_skill.run(); diff --git a/session/crane_planner_plugins/src/emplace_robot_planner.cpp b/session/crane_planner_plugins/src/emplace_robot_planner.cpp index f329527ec..537993503 100644 --- a/session/crane_planner_plugins/src/emplace_robot_planner.cpp +++ b/session/crane_planner_plugins/src/emplace_robot_planner.cpp @@ -57,7 +57,7 @@ auto EmplaceRobotPlanner::getSelectedRobots( if (select_num <= selected.size()) { break; } - if (goalie_id != id) { + if (100 == selectable_robots_num || goalie_id != id) { selected.emplace_back(id); } } diff --git a/session/crane_session_controller/config/normal.yaml b/session/crane_session_controller/config/normal.yaml index 048630d89..527eb24b8 100644 --- a/session/crane_session_controller/config/normal.yaml +++ b/session/crane_session_controller/config/normal.yaml @@ -57,3 +57,7 @@ events: session: simple_ai - event: INJECTION session: HALT + - event: OUR_TIMEOUT + session: emplace_robot + - event: THEIR_TIMEOUT + session: emplace_robot diff --git a/session/crane_session_controller/config/play_situation/emplace.yaml b/session/crane_session_controller/config/play_situation/emplace.yaml new file mode 100644 index 000000000..2a973a273 --- /dev/null +++ b/session/crane_session_controller/config/play_situation/emplace.yaml @@ -0,0 +1,7 @@ +name: emplace_robot +description: emplace_robot +sessions: + - name: emplace_robot + capacity: 100 + - name: waiter + capacity: 20 diff --git a/utility/crane_msg_wrappers/include/crane_msg_wrappers/robot_command_wrapper.hpp b/utility/crane_msg_wrappers/include/crane_msg_wrappers/robot_command_wrapper.hpp index bddf80548..7c8f9a733 100644 --- a/utility/crane_msg_wrappers/include/crane_msg_wrappers/robot_command_wrapper.hpp +++ b/utility/crane_msg_wrappers/include/crane_msg_wrappers/robot_command_wrapper.hpp @@ -321,7 +321,9 @@ class RobotCommandWrapperPosition : public RobotCommandWrapperCommonrobot->pose.pos); + return setTargetPosition(command->robot->pose.pos) + .setTargetTheta(command->robot->pose.theta) + .setOmegaLimit(0.); } }; diff --git a/utility/crane_msg_wrappers/src/play_situation_wrapper.cpp b/utility/crane_msg_wrappers/src/play_situation_wrapper.cpp index 02a4dd3ab..d623fb32a 100644 --- a/utility/crane_msg_wrappers/src/play_situation_wrapper.cpp +++ b/utility/crane_msg_wrappers/src/play_situation_wrapper.cpp @@ -54,6 +54,8 @@ static std::map situation_command_map = { CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, THEIR_DIRECT_FREE), CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, OUR_BALL_PLACEMENT), CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, THEIR_BALL_PLACEMENT), + CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, OUR_TIMEOUT), + CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, THEIR_TIMEOUT), CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, INJECTION), CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, INPLAY), CMD_STRING_MAPPING(crane_msgs::msg::PlaySituation, OUR_INPLAY),