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
2 changes: 2 additions & 0 deletions src/bt_core/src/MissionChecker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,10 +81,12 @@ BT::NodeStatus MissionChecker::onRunning() {
if(action_ == ActionType::TAKE){
robot_side_status[side_idx_] = FieldStatus::OCCUPIED;
blackboard_->set<std::vector<FieldStatus>>("robot_side_status", robot_side_status);
MC_INFO(node_, "Marking side %d as OCCUPIED due to TAKE timeout", side_idx_);
}
else if(action_ == ActionType::PUT){
robot_side_status[side_idx_] = FieldStatus::EMPTY;
blackboard_->set<std::vector<FieldStatus>>("robot_side_status", robot_side_status);
MC_INFO(node_, "Marking side %d as EMPTY due to PUT timeout", side_idx_);
}
return BT::NodeStatus::SUCCESS; // Don't block the game
}
Expand Down
2 changes: 1 addition & 1 deletion src/sensors/src/FirmwareReceiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,6 @@ void FirmwareReceiver::takeFinishCallback(const std_msgs::msg::Int16::SharedPtr
}

BT::NodeStatus FirmwareReceiver::tick() {
RCLCPP_DEBUG(node_->get_logger(), "FirmwareReceiver tick");
RCLCPP_DEBUG(node_->get_logger(), "[FirmwareReceiver]: tick");
return BT::NodeStatus::SUCCESS;
}
5 changes: 4 additions & 1 deletion src/startup/include/startup.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,9 +77,11 @@ class StartUp : public rclcpp::Node {
// game timer
rclcpp::TimerBase::SharedPtr timer;
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr game_time_pub;
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr sima_game_over_pub;
std::shared_ptr<rclcpp::Rate> rate;
int game_time;
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

game_time is declared as int here, but the implementation treats it as elapsed seconds (Float32/double). This can cause truncation and printf-format mismatches. Consider changing this member to double/float.

Suggested change
int game_time;
double game_time;

Copilot uses AI. Check for mistakes.

bool sima_game_over_sent;

// State checker for other groups
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr are_you_ready_pub;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr plan_file_pub;
Expand Down Expand Up @@ -123,6 +125,7 @@ class StartUp : public rclcpp::Node {
std::vector<double> yellow_start_pose;
int time_rate;
int game_time_limit;
int sima_game_over_trigger_sec;
int sima_tick_threshold;
int group_num;
};
1 change: 1 addition & 0 deletions src/startup/params/robot_config_black.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
time_rate: 100 # Timer rate in microseconds (100 = 10kHz)
game_time: 100 # Total game time in seconds
sima_tick_threshold: 85 # Seconds before sima starts
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment grammar: "Seconds tell sima to stop" is unclear; consider rephrasing (e.g., "Seconds after start to tell Sima to stop").

Suggested change
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
sima_game_over_trigger_sec: 99 # Seconds after game start to tell Sima to stop

Copilot uses AI. Check for mistakes.
group_num: 5 # Total number of groups (including index 0)

# Plan Configuration
Expand Down
1 change: 1 addition & 0 deletions src/startup/params/robot_config_default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
time_rate: 100 # Timer rate in microseconds (100 = 10kHz)
game_time: 100 # Total game time in seconds
sima_tick_threshold: 85 # Seconds before sima starts
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
Comment on lines 8 to +9
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment grammar: "Seconds tell sima to stop" is unclear; consider rephrasing (e.g., "Seconds after start to tell Sima to stop").

Suggested change
sima_tick_threshold: 85 # Seconds before sima starts
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
sima_tick_threshold: 85 # Seconds before Sima starts
sima_game_over_trigger_sec: 99 # Seconds after start to tell Sima to stop

Copilot uses AI. Check for mistakes.
group_num: 5 # Total number of groups (including index 0)

# Plan Configuration
Expand Down
1 change: 1 addition & 0 deletions src/startup/params/robot_config_white.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
time_rate: 100 # Timer rate in microseconds (100 = 10kHz)
game_time: 100 # Total game time in seconds
sima_tick_threshold: 85 # Seconds before sima starts
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment grammar: "Seconds tell sima to stop" is unclear; consider rephrasing (e.g., "Seconds after start to tell Sima to stop").

Suggested change
sima_game_over_trigger_sec: 99 # Seconds tell sima to stop
sima_game_over_trigger_sec: 99 # Seconds after start to tell Sima to stop

Copilot uses AI. Check for mistakes.
group_num: 5 # Total number of groups (including index 0)

# Plan Configuration
Expand Down
13 changes: 13 additions & 0 deletions src/startup/src/startup_new.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ StartUp::StartUp() : Node("startup_node"){

game_time_pub = this->create_publisher<std_msgs::msg::Float32>("/robot/startup/game_time", 2);
rate = std::make_shared<rclcpp::Rate>(time_rate);
sima_game_over_pub = this->create_publisher<std_msgs::msg::Bool>("/robot/startup/sima_game_over", 1);
Comment on lines 14 to +16
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The /robot/startup/sima_game_over topic looks like a one-shot event; with a depth-only QoS, late subscribers can miss it. Consider using a reliable + transient_local QoS (similar to src/navigation/src/stop_robot_node.cpp:5) so consumers that start after this publish still receive the last "game over" signal.

Copilot uses AI. Check for mistakes.

// State checker for other groups
are_you_ready_pub = this->create_publisher<std_msgs::msg::Bool>("/robot/startup/are_you_ready", 2);
Expand Down Expand Up @@ -50,13 +51,15 @@ StartUp::StartUp() : Node("startup_node"){
is_plugged = false;
end_logged = false;
game_time = 0;
sima_game_over_sent = false;
}

void StartUp::initParam() {
// Timing parameters
this->declare_parameter<int>("time_rate", 100);
this->declare_parameter<int>("game_time", 100);
this->declare_parameter<int>("sima_tick_threshold", 85);
this->declare_parameter<int>("sima_game_over_trigger_sec", 99);
this->declare_parameter<int>("group_num", 5);

// Robot parameters
Expand All @@ -69,6 +72,7 @@ void StartUp::initParam() {
this->get_parameter("time_rate", time_rate);
this->get_parameter("game_time", game_time_limit);
this->get_parameter("sima_tick_threshold", sima_tick_threshold);
this->get_parameter("sima_game_over_trigger_sec", sima_game_over_trigger_sec);
this->get_parameter("group_num", group_num);

// Get robot parameters
Expand Down Expand Up @@ -288,6 +292,15 @@ void StartUp::publishTime() {
cur_time_msg.data = cur_time - start_time;
game_time = cur_time_msg.data;
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

game_time is an int, but here it’s assigned from a Float32 seconds value (cur_time_msg.data). This truncates elapsed time and can make time-based thresholds fire later/earlier than intended. Consider changing game_time to double/float (and keeping comparisons consistent).

Suggested change
game_time = cur_time_msg.data;
game_time = static_cast<int>(cur_time_msg.data);

Copilot uses AI. Check for mistakes.
game_time_pub->publish(cur_time_msg);

if (!sima_game_over_sent && game_time >= sima_game_over_trigger_sec) {
std_msgs::msg::Bool msg;
msg.data = true;
sima_game_over_pub->publish(msg);
sima_game_over_sent = true;
RCLCPP_INFO(this->get_logger(), "[StartUp]: Sima game over signal sent at game time %f", game_time);
}
Comment on lines +299 to +302
Copy link

Copilot AI Mar 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

RCLCPP_INFO uses printf-style formatting; %f expects a double, but game_time is currently an int. This mismatch is undefined behavior. Fix by changing game_time’s type to double/float or casting to double in the log call (and adjusting the member type in the header accordingly).

Copilot uses AI. Check for mistakes.

tickLittleSima(game_time);
}

Expand Down