mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-01-18 16:47:43 +01:00
timeout
This commit is contained in:
@@ -42,5 +42,6 @@ namespace Modelec
|
|||||||
Point spawn_;
|
Point spawn_;
|
||||||
|
|
||||||
rclcpp::Time deploy_time_;
|
rclcpp::Time deploy_time_;
|
||||||
|
rclcpp::Time go_timeout_;
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -22,6 +22,8 @@ namespace Modelec
|
|||||||
|
|
||||||
nav_->GoTo(spawn_.x, 160, M_PI_2, true, Pathfinding::FREE | Pathfinding::WALL | Pathfinding::OBSTACLE);
|
nav_->GoTo(spawn_.x, 160, M_PI_2, true, Pathfinding::FREE | Pathfinding::WALL | Pathfinding::OBSTACLE);
|
||||||
|
|
||||||
|
go_timeout_ = node_->now();
|
||||||
|
|
||||||
status_ = MissionStatus::RUNNING;
|
status_ = MissionStatus::RUNNING;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -37,9 +39,12 @@ namespace Modelec
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!nav_->HasArrived())
|
if (!nav_->HasArrived() && (node_->now() - go_timeout_).seconds() < 2)
|
||||||
{
|
{
|
||||||
return;
|
if ((node_->now() - go_timeout_).seconds() < 4)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (step_)
|
switch (step_)
|
||||||
@@ -74,6 +79,7 @@ namespace Modelec
|
|||||||
|
|
||||||
case UNDEPLOY_BANNER:
|
case UNDEPLOY_BANNER:
|
||||||
{
|
{
|
||||||
|
go_timeout_ = node_->now();
|
||||||
nav_->GoTo(spawn_.x, (nav_->GetPathfinding()->robot_length_mm_ / 2) + 550, M_PI_2, true, Pathfinding::FREE | Pathfinding::WALL | Pathfinding::OBSTACLE);
|
nav_->GoTo(spawn_.x, (nav_->GetPathfinding()->robot_length_mm_ / 2) + 550, M_PI_2, true, Pathfinding::FREE | Pathfinding::WALL | Pathfinding::OBSTACLE);
|
||||||
|
|
||||||
step_ = GO_FORWARD;
|
step_ = GO_FORWARD;
|
||||||
|
|||||||
Reference in New Issue
Block a user