Skip to content

Commit 6dd9fce

Browse files
authored
Merge pull request #163 from ibis-ssl/test_autoref
AutoRefのお試しをやりながらバグを潰していく
2 parents 5e0db97 + 2ecfcbd commit 6dd9fce

File tree

11 files changed

+49
-33
lines changed

11 files changed

+49
-33
lines changed
+1
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
11
std_msgs/Header header
2+
bool on_positive_half
23
bool is_yellow
34
RobotCommand[] robot_commands

crane_msgs/msg/world_model/WorldModel.msg

+1-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
std_msgs/Header header
22

3+
bool on_positive_half
34
bool is_yellow
45

56
uint8 our_goalie_id
@@ -14,6 +15,4 @@ BallInfo ball_info
1415
RobotInfoOurs[] robot_info_ours
1516
RobotInfoTheirs[] robot_info_theirs
1617

17-
geometry_msgs/Point ball_placement_target
18-
1918
PlaySituation play_situation

crane_play_switcher/src/play_switcher.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -187,6 +187,11 @@ void PlaySwitcher::referee_callback(const robocup_ssl_msgs::msg::Referee & msg)
187187
last_command_changed_state.stamp = now();
188188
last_command_changed_state.ball_position = world_model->ball.pos;
189189

190+
if (msg.designated_position.size() > 0) {
191+
play_situation_msg.placement_position.x = msg.designated_position[0].x;
192+
play_situation_msg.placement_position.y = msg.designated_position[0].y;
193+
}
194+
190195
// パブリッシュはコマンド更新時のみ
191196
play_situation_pub->publish(play_situation_msg);
192197
}

crane_sender/src/ibis_sender_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ class IbisSenderNode : public SenderBase
113113

114114
for (auto command : msg.robot_commands) {
115115
//
116-
if (msg.is_yellow) {
116+
if (not msg.on_positive_half) {
117117
command.target_velocity.x *= -1;
118118
command.target_velocity.y *= -1;
119119
command.target_velocity.theta *= -1;

crane_simple_ai/include/crane_commander.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ class ROSNode : public rclcpp::Node
110110
crane_msgs::msg::RobotCommands msg;
111111
msg.header = world_model->getMsg().header;
112112
msg.is_yellow = world_model->isYellow();
113+
msg.on_positive_half = world_model->onPositiveHalf();
113114
msg.robot_commands.push_back(latest_msg);
114115
publisher_robot_commands->publish(msg);
115116
});

crane_world_model_publisher/include/crane_world_model_publisher/world_model_publisher.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,8 @@ class WorldModelPublisherComponent : public rclcpp::Node
9191

9292
Color their_color;
9393

94+
bool on_positive_half;
95+
9496
uint8_t our_goalie_id, their_goalie_id;
9597

9698
uint8_t max_id;

crane_world_model_publisher/src/world_model_publisher.cpp

+17-14
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,16 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(const rclcpp::NodeOpt
3838
declare_parameter("team_name", "ibis-ssl");
3939
team_name = get_parameter("team_name").as_string();
4040

41+
declare_parameter("initial_team_color", "BLUE");
42+
auto initial_team_color = get_parameter("initial_team_color").as_string();
43+
if (initial_team_color == "BLUE") {
44+
our_color = Color::BLUE;
45+
their_color = Color::YELLOW;
46+
} else {
47+
our_color = Color::YELLOW;
48+
their_color = Color::BLUE;
49+
}
50+
4151
sub_referee = this->create_subscription<robocup_ssl_msgs::msg::Referee>(
4252
"/referee", 1, [this](const robocup_ssl_msgs::msg::Referee & msg) {
4353
if (msg.yellow.name == team_name) {
@@ -46,12 +56,18 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(const rclcpp::NodeOpt
4656
their_color = Color::BLUE;
4757
our_goalie_id = msg.yellow.goalkeeper;
4858
their_goalie_id = msg.blue.goalkeeper;
59+
if (not msg.blue_team_on_positive_half.empty()) {
60+
on_positive_half = not msg.blue_team_on_positive_half[0];
61+
}
4962
} else if (msg.blue.name == team_name) {
5063
// BLUE
5164
our_color = Color::BLUE;
5265
their_color = Color::YELLOW;
5366
our_goalie_id = msg.blue.goalkeeper;
5467
their_goalie_id = msg.yellow.goalkeeper;
68+
if (not msg.blue_team_on_positive_half.empty()) {
69+
on_positive_half = msg.blue_team_on_positive_half[0];
70+
}
5571
} else {
5672
std::stringstream what;
5773
what << "Cannot find our team name, " << team_name << " in referee message. ";
@@ -64,17 +80,6 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(const rclcpp::NodeOpt
6480
ball_placement_target_y = msg.designated_position.front().y / 1000.;
6581
}
6682
});
67-
68-
declare_parameter("initial_team_color", "BLUE");
69-
auto initial_team_color = get_parameter("initial_team_color").as_string();
70-
if (initial_team_color == "BLUE") {
71-
our_color = Color::BLUE;
72-
their_color = Color::YELLOW;
73-
74-
} else {
75-
our_color = Color::YELLOW;
76-
their_color = Color::BLUE;
77-
}
7883
}
7984

8085
void WorldModelPublisherComponent::visionDetectionsCallback(
@@ -164,6 +169,7 @@ void WorldModelPublisherComponent::publishWorldModel()
164169
crane_msgs::msg::WorldModel wm;
165170

166171
wm.is_yellow = (our_color == Color::YELLOW);
172+
wm.on_positive_half = on_positive_half;
167173
wm.ball_info = ball_info;
168174

169175
updateBallContact();
@@ -196,9 +202,6 @@ void WorldModelPublisherComponent::publishWorldModel()
196202
wm.goal_size.x = goal_h;
197203
wm.goal_size.y = goal_w;
198204

199-
wm.ball_placement_target.x = ball_placement_target_x;
200-
wm.ball_placement_target.y = ball_placement_target_y;
201-
202205
wm.our_goalie_id = our_goalie_id;
203206
wm.their_goalie_id = their_goalie_id;
204207

session/crane_planner_base/include/crane_planner_base/planner_base.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,8 @@ class PlannerBase
6969
status = latest_status;
7070
crane_msgs::msg::RobotCommands msg;
7171
msg.is_yellow = world_model->isYellow();
72-
for (auto command : robot_commands) {
72+
msg.on_positive_half = world_model->onPositiveHalf();
73+
for (const auto & command : robot_commands) {
7374
msg.robot_commands.emplace_back(command);
7475
}
7576
return msg;

session/crane_session_controller/src/crane_session_controller.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -142,6 +142,7 @@ SessionControllerComponent::SessionControllerComponent(const rclcpp::NodeOptions
142142
world_model->addCallback([this]() {
143143
crane_msgs::msg::RobotCommands msg;
144144
msg.header = world_model->getMsg().header;
145+
msg.on_positive_half = world_model->onPositiveHalf();
145146
msg.is_yellow = world_model->isYellow();
146147
for (const auto & planner : available_planners) {
147148
auto commands_msg = planner->getRobotCommands();

utility/crane_msg_wrappers/include/crane_msg_wrappers/world_model_wrapper.hpp

+17-14
Original file line numberDiff line numberDiff line change
@@ -257,9 +257,9 @@ struct WorldModelWrapper
257257
defense_area_size << world_model.defense_area_size.x, world_model.defense_area_size.y;
258258

259259
goal_size << world_model.goal_size.x, world_model.goal_size.y;
260-
goal << (isYellow() ? field_size.x() * 0.5 : -field_size.x() * 0.5), 0.;
260+
goal << getOurSideSign() * field_size.x() * 0.5, 0.;
261261

262-
if (goal.x() > 0) {
262+
if (onPositiveHalf()) {
263263
ours.defense_area.max_corner() << goal.x(), goal.y() + world_model.defense_area_size.y / 2.;
264264
ours.defense_area.min_corner() << goal.x() - world_model.defense_area_size.x,
265265
goal.y() - world_model.defense_area_size.y / 2.;
@@ -274,19 +274,14 @@ struct WorldModelWrapper
274274
theirs.defense_area.min_corner()
275275
<< std::min(-ours.defense_area.max_corner().x(), -ours.defense_area.min_corner().x()),
276276
ours.defense_area.min_corner().y();
277-
278-
if (
279-
world_model.play_situation.command == crane_msgs::msg::PlaySituation::OUR_BALL_PLACEMENT or
280-
world_model.play_situation.command == crane_msgs::msg::PlaySituation::THEIR_BALL_PLACEMENT) {
281-
*ball_placement_target << world_model.ball_placement_target.x,
282-
world_model.ball_placement_target.y;
283-
} else {
284-
ball_placement_target = std::nullopt;
285-
}
286277
}
287278

288279
[[nodiscard]] const crane_msgs::msg::WorldModel & getMsg() const { return latest_msg; }
289280

281+
[[nodiscard]] bool onPositiveHalf() const { return (latest_msg.on_positive_half); }
282+
283+
[[nodiscard]] double getOurSideSign() const { return onPositiveHalf() ? 1.0 : -1.0; }
284+
290285
[[nodiscard]] bool isYellow() const { return (latest_msg.is_yellow); }
291286

292287
[[nodiscard]] bool hasUpdated() const { return has_updated; }
@@ -456,16 +451,24 @@ struct WorldModelWrapper
456451

457452
[[nodiscard]] std::optional<Point> getBallPlacementTarget() const
458453
{
459-
return ball_placement_target;
454+
if (
455+
play_situation.getSituationCommandID() ==
456+
crane_msgs::msg::PlaySituation::OUR_BALL_PLACEMENT or
457+
play_situation.getSituationCommandID() ==
458+
crane_msgs::msg::PlaySituation::THEIR_BALL_PLACEMENT) {
459+
return play_situation.placement_position;
460+
} else {
461+
return std::nullopt;
462+
}
460463
}
461464

462465
// rule 8.4.3
463466
[[nodiscard]] std::optional<Capsule> getBallPlacementArea() const
464467
{
465-
if (ball_placement_target) {
468+
if (auto target = getBallPlacementTarget()) {
466469
Capsule area;
467470
area.segment.first = ball.pos;
468-
area.segment.second = ball_placement_target.value();
471+
area.segment.second = target.value();
469472
area.radius = 0.5;
470473
return area;
471474
} else {

utility/crane_msg_wrappers/src/play_situation_wrapper.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ auto PlaySituationWrapper::update(const crane_msgs::msg::PlaySituation & msg) ->
6666
situation_command.id = msg.command;
6767
situation_command.text = situation_command_map[msg.command];
6868

69-
placement_position << msg.placement_position.x, msg.placement_position.y;
69+
placement_position << msg.placement_position.x / 1000., msg.placement_position.y / 1000.;
7070
}
7171

7272
auto PlaySituationWrapper::getRefereeCommandText(uint32_t id) -> std::string

0 commit comments

Comments
 (0)