This commit is contained in:
acki
2025-05-29 18:18:22 -04:00
parent d711c6813f
commit 760453c928
2 changed files with 2 additions and 2 deletions

View File

@@ -28,7 +28,7 @@ namespace Modelec
robot_length_ = Config::get<float>("config.robot.size.length_mm", 500.0);
robot_radius_ = std::max(robot_width_, robot_length_) / 3.0;
min_emergency_distance_ = Config::get<float>("config.enemy.detection.min_emergency_distance_mm", 100.0);
min_emergency_distance_ = Config::get<float>("config.enemy.detection.min_emergency_distance_mm", 500.0f);
current_pos_sub_ = this->create_subscription<modelec_interfaces::msg::OdometryPos>(
"odometry/position", 10,

View File

@@ -553,7 +553,7 @@ namespace Modelec
if (last_was_close_enemy_)
{
if (Point::distance(Point(msg->x, msg->y, msg->theta), Point(current_pos_->x, current_pos_->y, current_pos_->theta)) > 700)
if (Point::distance(Point(msg->x, msg->y, msg->theta), Point(current_pos_->x, current_pos_->y, current_pos_->theta)) > 600)
{
RCLCPP_INFO(node_->get_logger(), "Enemy was close try to replanning...");
if (Replan(false))