mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-03-18 21:50:36 +01:00
refactoring
This commit is contained in:
@@ -87,12 +87,12 @@ class SimulatedPCB:
|
|||||||
if category == "ASC":
|
if category == "ASC":
|
||||||
self.ascenseur_pos = data
|
self.ascenseur_pos = data
|
||||||
self.send_response(f"OK;{category};{data}")
|
self.send_response(f"OK;{category};{data}")
|
||||||
time.sleep(2)
|
time.sleep(.5)
|
||||||
elif category.startswith("SERVO") and data.startswith("POS"):
|
elif category.startswith("SERVO") and data.startswith("POS"):
|
||||||
sid = int(category[5:])
|
sid = int(category[5:])
|
||||||
pos_index = int(data[3:])
|
pos_index = int(data[3:])
|
||||||
if sid in self.servo_angles and pos_index in self.servo_angles[sid]:
|
if sid in self.servo_angles and pos_index in self.servo_angles[sid]:
|
||||||
time.sleep(0.5)
|
time.sleep(0.1)
|
||||||
self.servos[sid] = pos_index
|
self.servos[sid] = pos_index
|
||||||
self.send_response(f"OK;{category};{data}")
|
self.send_response(f"OK;{category};{data}")
|
||||||
else:
|
else:
|
||||||
@@ -100,7 +100,7 @@ class SimulatedPCB:
|
|||||||
elif category.startswith("RELAY"):
|
elif category.startswith("RELAY"):
|
||||||
rid = int(category[5:])
|
rid = int(category[5:])
|
||||||
self.relais[rid] = 1 if data == "1" else 0
|
self.relais[rid] = 1 if data == "1" else 0
|
||||||
time.sleep(.2)
|
time.sleep(.1)
|
||||||
self.send_response(f"OK;{category};{data}")
|
self.send_response(f"OK;{category};{data}")
|
||||||
else:
|
else:
|
||||||
self.send_response(f"KO;{category};{data}")
|
self.send_response(f"KO;{category};{data}")
|
||||||
|
|||||||
@@ -29,19 +29,16 @@ namespace Modelec
|
|||||||
{
|
{
|
||||||
if (status_ != MissionStatus::RUNNING)
|
if (status_ != MissionStatus::RUNNING)
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(node_->get_logger(), "Mission not running");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!action_executor_->IsActionDone())
|
if (!action_executor_->IsActionDone())
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(node_->get_logger(), "Waiting for action to finish");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!nav_->HasArrived())
|
if (!nav_->HasArrived())
|
||||||
{
|
{
|
||||||
RCLCPP_INFO(node_->get_logger(), "Waiting for navigation to finish");
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -34,7 +34,10 @@ namespace Modelec
|
|||||||
|
|
||||||
void GoHomeMission::Update()
|
void GoHomeMission::Update()
|
||||||
{
|
{
|
||||||
if (!nav_->HasArrived()) return;
|
if (!nav_->HasArrived())
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
switch (step_)
|
switch (step_)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -5,7 +5,8 @@
|
|||||||
namespace Modelec
|
namespace Modelec
|
||||||
{
|
{
|
||||||
PrepareConcertMission::PrepareConcertMission(const std::shared_ptr<NavigationHelper>& nav,
|
PrepareConcertMission::PrepareConcertMission(const std::shared_ptr<NavigationHelper>& nav,
|
||||||
const std::shared_ptr<ActionExecutor>& action_executor, bool two_floor) :
|
const std::shared_ptr<ActionExecutor>& action_executor,
|
||||||
|
bool two_floor) :
|
||||||
step_(GO_TO_COLUMN),
|
step_(GO_TO_COLUMN),
|
||||||
status_(MissionStatus::READY), nav_(nav), action_executor_(action_executor), two_floor_(two_floor)
|
status_(MissionStatus::READY), nav_(nav), action_executor_(action_executor), two_floor_(two_floor)
|
||||||
{
|
{
|
||||||
@@ -18,7 +19,8 @@ namespace Modelec
|
|||||||
if (two_floor_)
|
if (two_floor_)
|
||||||
{
|
{
|
||||||
mission_score_ = Config::get<int>("config.mission_score.concert.niv_2", 0);
|
mission_score_ = Config::get<int>("config.mission_score.concert.niv_2", 0);
|
||||||
} else
|
}
|
||||||
|
else
|
||||||
{
|
{
|
||||||
mission_score_ = Config::get<int>("config.mission_score.concert.niv_1", 0);
|
mission_score_ = Config::get<int>("config.mission_score.concert.niv_1", 0);
|
||||||
}
|
}
|
||||||
@@ -68,11 +70,20 @@ namespace Modelec
|
|||||||
|
|
||||||
void PrepareConcertMission::Update()
|
void PrepareConcertMission::Update()
|
||||||
{
|
{
|
||||||
if (status_ != MissionStatus::RUNNING) return;
|
if (status_ != MissionStatus::RUNNING)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (!nav_->HasArrived()) return;
|
if (!nav_->HasArrived())
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
if (!action_executor_->IsActionDone()) return;
|
if (!action_executor_->IsActionDone())
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
switch (step_)
|
switch (step_)
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user