Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions launch/soccer.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -245,6 +245,13 @@ def generate_launch_description():
parameters=[param_config_filepath],
on_exit=Shutdown(),
),
Node(
package="rj_strategy",
executable="seeking_coordinator_node",
output="screen",
parameters=[param_config_filepath],
on_exit=Shutdown(),
),
Node(
package="rj_strategy",
executable="waller_node",
Expand Down
3 changes: 2 additions & 1 deletion src/rj_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ rosidl_generate_interfaces(

# Coordinators
msg/KickerPicker.msg
msg/SeekingCoordinator.msg
msg/Waller.msg

# Agent Request Messages
Expand All @@ -68,7 +69,6 @@ rosidl_generate_interfaces(
request/PassRequest.msg
request/ScorerRequest.msg
request/BallInTransitRequest.msg
request/SeekerRequest.msg
request/PositionRequest.msg
request/LeaveWallRequest.msg
request/ResetScorerRequest.msg
Expand All @@ -86,6 +86,7 @@ rosidl_generate_interfaces(
# Services
srv/AgentCommunication.srv
srv/KickerPicker.srv
srv/SeekingCoordinator.srv
srv/Waller.srv
srv/ListJoysticks.srv
srv/PlanHypotheticalPath.srv
Expand Down
1 change: 0 additions & 1 deletion src/rj_msgs/msg/AgentRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@ TestRequest[<=1] test_request
PassRequest[<=1] pass_request
ScorerRequest[<=1] scorer_request
BallInTransitRequest[<=1] ball_in_transit_request
SeekerRequest[<=1] seeker_request
PositionRequest[<=1] position_request
LeaveWallRequest[<=1] leave_wall_request
ResetScorerRequest[<=1] reset_scorer_request
Expand Down
2 changes: 2 additions & 0 deletions src/rj_msgs/msg/SeekingCoordinator.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# This is a message to publish the current seekers' chosen positions
rj_geometry_msgs/Point[16] positions
9 changes: 0 additions & 9 deletions src/rj_msgs/request/SeekerRequest.msg

This file was deleted.

5 changes: 5 additions & 0 deletions src/rj_msgs/srv/SeekingCoordinator.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# Request a robot to be added to or removed from seekers
uint8 robot_id # ID of the robot (0 to kNumShells-1)
bool wants_to_seek # True to add robot to seekers, false to remove.
---
bool success # Always true
21 changes: 19 additions & 2 deletions src/rj_strategy/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ set(RJ_STRATEGY_SRC
src/agent/position/penalty_player.cpp
src/agent/position/pivot_test.cpp
src/agent/position/robot_factory_position.cpp
src/agent/position/seeker.cpp
src/agent/position/smartidling.cpp
src/agent/position/solo_offense.cpp
src/agent/position/zoner.cpp
Expand All @@ -63,6 +62,7 @@ set(RJ_STRATEGY_SRC

# Coordinators
src/coordinator/kicker_picker_client.cpp
src/coordinator/seeking_client.cpp
src/coordinator/waller_client.cpp
)

Expand Down Expand Up @@ -115,6 +115,23 @@ ament_target_dependencies(kicker_picker_node
${RJ_STRATEGY_DEPS}
)

# Seeker Node
add_executable(seeking_coordinator_node
${RJ_STRATEGY_SRC}
src/coordinator/seeking_client.cpp
src/coordinator/seeking_coordinator.cpp
)

target_include_directories(seeking_coordinator_node
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

ament_target_dependencies(seeking_coordinator_node
${RJ_STRATEGY_DEPS}
)

# Waller Node
add_executable(waller_node
${RJ_STRATEGY_SRC}
Expand Down Expand Up @@ -163,7 +180,7 @@ install(
)

install(
TARGETS straight_line_test_node kicker_picker_node waller_node agent_action_clients
TARGETS straight_line_test_node kicker_picker_node seeking_coordinator_node waller_node agent_action_clients
DESTINATION lib/${PROJECT_NAME}
)

Expand Down
12 changes: 3 additions & 9 deletions src/rj_strategy/include/rj_strategy/agent/communication.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include "rj_strategy/agent/communication/reset_scorer_request.hpp"
#include "rj_strategy/agent/communication/scorer_request.hpp"
#include "rj_strategy/agent/communication/scorer_response.hpp"
#include "rj_strategy/agent/communication/seeker_request.hpp"
#include "rj_strategy/agent/communication/test_request.hpp"
#include "rj_strategy/agent/communication/test_response.hpp"

Expand All @@ -34,9 +33,9 @@ namespace strategy::communication {
/**
* @brief a conglomeration of the different request types.
*/
using AgentRequest = std::variant<JoinWallRequest, TestRequest, PassRequest, ScorerRequest,
BallInTransitRequest, SeekerRequest, PositionRequest,
LeaveWallRequest, ResetScorerRequest, IncomingBallRequest>;
using AgentRequest =
std::variant<JoinWallRequest, TestRequest, PassRequest, ScorerRequest, BallInTransitRequest,
PositionRequest, LeaveWallRequest, ResetScorerRequest, IncomingBallRequest>;

/**
* @brief a conglomeration of the different response types.
Expand Down Expand Up @@ -144,9 +143,6 @@ struct RosConverter<strategy::communication::AgentRequest, rj_msgs::msg::AgentRe
} else if (const auto* ball_in_transit_request =
std::get_if<strategy::communication::BallInTransitRequest>(&from)) {
result.ball_in_transit_request.emplace_back(convert_to_ros(*ball_in_transit_request));
} else if (const auto* seeker_request =
std::get_if<strategy::communication::SeekerRequest>(&from)) {
result.seeker_request.emplace_back(convert_to_ros(*seeker_request));
} else if (const auto* position_request =
std::get_if<strategy::communication::PositionRequest>(&from)) {
result.position_request.emplace_back(convert_to_ros(*position_request));
Expand Down Expand Up @@ -177,8 +173,6 @@ struct RosConverter<strategy::communication::AgentRequest, rj_msgs::msg::AgentRe
result = convert_from_ros(from.scorer_request.front());
} else if (!from.ball_in_transit_request.empty()) {
result = convert_from_ros(from.ball_in_transit_request.front());
} else if (!from.seeker_request.empty()) {
result = convert_from_ros(from.seeker_request.front());
} else if (!from.position_request.empty()) {
result = convert_from_ros(from.position_request.front());
} else if (!from.leave_wall_request.empty()) {
Expand Down

This file was deleted.

2 changes: 2 additions & 0 deletions src/rj_strategy/include/rj_strategy/agent/position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@

// Coordinators
#include "rj_strategy/coordinator/kicker_picker_client.hpp"
#include "rj_strategy/coordinator/seeking_client.hpp"
#include "rj_strategy/coordinator/waller_client.hpp"

// tell compiler this class exists, but no need to import the whole header
Expand All @@ -52,6 +53,7 @@ namespace strategy {
// Client Handles for coordinators
struct ClientHandles {
std::unique_ptr<KickerPickerClient> kicker_picker;
std::unique_ptr<SeekingClient> seeking_client;
std::unique_ptr<WallerClient> waller;
};

Expand Down
13 changes: 5 additions & 8 deletions src/rj_strategy/include/rj_strategy/agent/position/offense.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include <rj_msgs/action/robot_move.hpp>

#include "rj_strategy/agent/position.hpp"
#include "rj_strategy/agent/position/seeker.hpp"
#include "rj_strategy/coordinator/seeking_client.hpp"

namespace strategy {

Expand All @@ -41,6 +41,8 @@ class Offense : public Position {

std::string get_current_state() override;

void die() override;

private:
/**
* @brief Overriden from Position. Calls next_state and then state_to_task on each tick.
Expand All @@ -49,7 +51,7 @@ class Offense : public Position {

enum State {
DEFAULT, // Decide what to do
SEEKING_START, // Calculate seeking point
SEEKING_START, // Join seeker group
SEEKING, // Get open
POSSESSION_START, // Try to shoot and send pass request
POSSESSION, // Holding the ball
Expand Down Expand Up @@ -164,8 +166,7 @@ class Offense : public Position {

int pass_to_robot_id_ = 0;

/* RoleInterface Members */
Seeker seeker_;
// TODO: Remove rj_geometry::Point seeker_target_;

// Used to cache targets between states
rj_geometry::Point target_;
Expand Down Expand Up @@ -227,10 +228,6 @@ class Offense : public Position {
* @return whether the ball is in an area that non-goalies cannot reach.
*/
bool ball_in_red() const;

void broadcast_seeker_request(rj_geometry::Point seeking_point, bool adding);

std::unordered_map<int, rj_geometry::Point> seeker_points_;
};

} // namespace strategy
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,8 @@ class RobotFactoryPosition : public Position {
}

bool set_position_override_if_requested();

std::shared_ptr<ClientHandles> clientHandles_;
};

} // namespace strategy
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace strategy {
* all handled by the Planner Node.
*
* Similiarly, this abstract superclass serves as an interface for all roles
* (ie. Waller, Marker, Seeker, etc.) to follow when being created. These roles
* (ie. Waller, Marker, etc.) to follow when being created. These roles
* will take in a robot intent from the Defense/Offense classes and output a new
* robot intent with the robot's next point depending on their role. The Defense/
* Offense classes will decide on what role the robot is currently playing based
Expand Down
Loading
Loading