Skip to content

Commit

Permalink
communication is properly forwarded to subclasses
Browse files Browse the repository at this point in the history
  • Loading branch information
p-nayak11 committed Nov 6, 2023
1 parent 7055351 commit b31191b
Show file tree
Hide file tree
Showing 6 changed files with 21 additions and 20 deletions.
7 changes: 2 additions & 5 deletions soccer/src/soccer/strategy/agent/agent_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,11 +128,6 @@ void AgentActionClient::get_task() {

auto optional_task = current_position_->get_task(last_world_state_, field_dimensions_);

if (robot_id_ == 1) {
SPDLOG_INFO("ID: {} get_task: {}", robot_id_, optional_task->motion_command.name);
}


if (optional_task.has_value()) {
RobotIntent task = optional_task.value();

Expand Down Expand Up @@ -289,6 +284,7 @@ void AgentActionClient::receive_communication_callback(
const std::shared_ptr<rj_msgs::srv::AgentCommunication::Request>& request,
const std::shared_ptr<rj_msgs::srv::AgentCommunication::Response>& response) {
if (current_position_ == nullptr) {
SPDLOG_INFO("I am getting stuck here!\n");
communication::AgentResponse agent_response;
communication::AgentRequest agent_request =
rj_convert::convert_from_ros(request->agent_request);
Expand All @@ -298,6 +294,7 @@ void AgentActionClient::receive_communication_callback(
agent_response.response = acknowledge;
response->agent_response = rj_convert::convert_to_ros(agent_response);
} else {
SPDLOG_INFO("I am NOT getting stuck here!\n");
// Convert agent request into AgentToPosCommRequest
communication::AgentPosRequestWrapper agent_request;
communication::AgentRequest received_request =
Expand Down
4 changes: 4 additions & 0 deletions soccer/src/soccer/strategy/agent/position/defense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,8 @@ void Defense::receive_communication_response(communication::AgentPosResponseWrap
// Call to super
Position::receive_communication_response(response);

SPDLOG_INFO("ID: {} is calling comm response!\n");

// Handle join wall response
if (const communication::JoinWallRequest* join_request =
std::get_if<communication::JoinWallRequest>(&response.associated_request)) {
Expand All @@ -146,6 +148,8 @@ communication::PosAgentResponseWrapper Defense::receive_communication_request(
communication::PosAgentResponseWrapper response =
Position::receive_communication_request(request);

SPDLOG_INFO("ID: {} is calling comm request!\n");

// Handle join and leave wall request
if (const communication::JoinWallRequest* join_request =
std::get_if<communication::JoinWallRequest>(&request.request)) {
Expand Down
4 changes: 2 additions & 2 deletions soccer/src/soccer/strategy/agent/position/offense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,9 @@ Offense::Offense(int r_id) : Position(r_id) {
}

std::optional<RobotIntent> Offense::derived_get_task(RobotIntent intent) {
SPDLOG_INFO("MY ID: {} in offense derived task!\n", robot_id_);
//SPDLOG_INFO("MY ID: {} in offense derived task!\n", robot_id_);
current_state_ = update_state();
SPDLOG_INFO("My current offense state is {}", current_state_);
//SPDLOG_INFO("My current offense state is {}", current_state_);
return state_to_task(intent);
}

Expand Down
2 changes: 1 addition & 1 deletion soccer/src/soccer/strategy/agent/position/position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class Position {
*
* @return communication::PosAgentRequestWrapper the request to be sent
*/
std::optional<communication::PosAgentRequestWrapper> send_communication_request();
virtual std::optional<communication::PosAgentRequestWrapper> send_communication_request();

/**
* @brief Receive the response from a sent request.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,27 +14,25 @@ if (robot_id_ == 0) {

}

std::optional<RobotIntent> RobotFactoryPosition::get_task(WorldState& ws, FieldDimensions& fd) {
return current_position_->get_task(ws, fd);
}

std::optional<RobotIntent> RobotFactoryPosition::derived_get_task(RobotIntent intent) {
std::optional<RobotIntent> RobotFactoryPosition::get_task(WorldState& world_state, FieldDimensions& field_dimensions) {
// This is where the current_position can be reassigned based on the
// PlayState
return current_position_->get_task(world_state, field_dimensions);
}


SPDLOG_ERROR("This should not be called");
std::optional<RobotIntent> RobotFactoryPosition::derived_get_task(RobotIntent intent) {

Check warning on line 23 in soccer/src/soccer/strategy/agent/position/robot_factory_position.cpp

View workflow job for this annotation

GitHub Actions / build-and-test

parameter 'intent' is unused
SPDLOG_ERROR("RobotFactory derived_get_task() should not be called!");
return std::nullopt;
}

// no longer called

// return current_position_->get_task(*last_world_state_, field_dimensions_);
std::optional<communication::PosAgentRequestWrapper> RobotFactoryPosition::send_communication_request() {
// Call to super
return current_position_->send_communication_request();
}

void RobotFactoryPosition::receive_communication_response(communication::AgentPosResponseWrapper response) {
// Call to super
current_position_->receive_communication_response(response);

}

communication::PosAgentResponseWrapper RobotFactoryPosition::receive_communication_request(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,12 @@ class RobotFactoryPosition : public Position {
std::optional<RobotIntent> get_task(WorldState&, FieldDimensions&) override;

Check warning on line 40 in soccer/src/soccer/strategy/agent/position/robot_factory_position.hpp

View workflow job for this annotation

GitHub Actions / build-and-test

all parameters should be named in a function

void receive_communication_response(communication::AgentPosResponseWrapper response) override;

communication::PosAgentResponseWrapper receive_communication_request(
communication::AgentPosRequestWrapper request) override;

std::optional<communication::PosAgentRequestWrapper> send_communication_request() override;

void derived_acknowledge_pass() override;
void derived_pass_ball() override;
void derived_acknowledge_ball_in_transit() override;
Expand All @@ -56,7 +59,6 @@ class RobotFactoryPosition : public Position {
std::unique_ptr<Position> current_position_;

std::optional<RobotIntent> derived_get_task(RobotIntent intent) override;

};

} // namespace strategy

0 comments on commit b31191b

Please sign in to comment.