diff --git a/src/modelec_strat/src/enemy_manager.cpp b/src/modelec_strat/src/enemy_manager.cpp index f0425e1..2e74591 100644 --- a/src/modelec_strat/src/enemy_manager.cpp +++ b/src/modelec_strat/src/enemy_manager.cpp @@ -219,7 +219,7 @@ namespace Modelec last_enemy_pos_ = enemy_pos; last_publish_time_ = this->now(); last_movement_time_ = this->now(); // Mise à jour du dernier vrai mouvement - enemy_pos_pub_->publish(enemy_pos); + // enemy_pos_pub_->publish(enemy_pos); // RCLCPP_INFO(this->get_logger(), "Enemy moved: x=%f, y=%f", enemy_pos.x, enemy_pos.y); } else @@ -227,7 +227,7 @@ namespace Modelec auto now = this->now(); if ((now - last_movement_time_).seconds() > max_stationary_time_s_) { - enemy_long_time_pub_->publish(last_enemy_pos_); + // enemy_long_time_pub_->publish(last_enemy_pos_); /*RCLCPP_WARN(this->get_logger(), "Enemy has been stationary for too long at x=%f y=%f", last_enemy_pos_.x, last_enemy_pos_.y);*/ diff --git a/src/modelec_strat/src/strat_fms.cpp b/src/modelec_strat/src/strat_fms.cpp index 51077f1..d2081e9 100644 --- a/src/modelec_strat/src/strat_fms.cpp +++ b/src/modelec_strat/src/strat_fms.cpp @@ -163,7 +163,10 @@ namespace Modelec { Transition(State::DO_PROMOTION, "Start promotion"); }*/ - Transition(State::DO_GO_HOME, "Go Home"); + if (elapsed.seconds() >= 2) + { + Transition(State::DO_GO_HOME, "Go Home"); + } // TODO : check the time needed by the mission /*else if (elapsed.seconds() < 70) {