mirror of
https://github.com/modelec/modelec-marcel-ROS.git
synced 2026-01-18 16:47:43 +01:00
banner
This commit is contained in:
@@ -209,7 +209,7 @@ namespace Modelec
|
||||
{2, {{0, M_PI_2}}},
|
||||
{3, {{0, M_PI_2}}},
|
||||
{4, {{0, 1.25}, {1, 0.45}}},
|
||||
{5, {{0, M_PI_2}}},
|
||||
{5, {{0, 0}, {1, M_PI}}},
|
||||
};
|
||||
|
||||
for (auto & [id, v] : servo_pos_mapper_)
|
||||
@@ -222,10 +222,10 @@ namespace Modelec
|
||||
|
||||
servo_value_ = {
|
||||
{0, 0},
|
||||
{1, 0},
|
||||
{1, 1},
|
||||
{2, 0},
|
||||
{3, 0},
|
||||
{4, 0},
|
||||
{4, 1},
|
||||
{5, 0}
|
||||
};
|
||||
|
||||
|
||||
@@ -55,20 +55,20 @@
|
||||
<pcb>
|
||||
<pcb_odo>
|
||||
<name>pcb_odo</name>
|
||||
<port>/dev/USB_ODO</port>
|
||||
<!--<port>/tmp/USB_ODO</port>-->
|
||||
<!--<port>/dev/USB_ODO</port>-->
|
||||
<port>/tmp/USB_ODO</port>
|
||||
<baud_rate>115200</baud_rate>
|
||||
</pcb_odo>
|
||||
<pcb_alim>
|
||||
<name>pcb_alim</name>
|
||||
<port>/dev/USB_ALIM</port>
|
||||
<!--<port>/tmp/USB_ALIM</port>-->
|
||||
<!--<port>/dev/USB_ALIM</port>-->
|
||||
<port>/tmp/USB_ALIM</port>
|
||||
<baud_rate>115200</baud_rate>
|
||||
</pcb_alim>
|
||||
<pcb_action>
|
||||
<name>pcb_action</name>
|
||||
<port>/dev/USB_ACTION</port>
|
||||
<!--<port>/tmp/USB_ACTION</port>-->
|
||||
<!--<port>/dev/USB_ACTION</port>-->
|
||||
<port>/tmp/USB_ACTION</port>
|
||||
<baud_rate>115200</baud_rate>
|
||||
</pcb_action>
|
||||
</pcb>
|
||||
|
||||
@@ -15,6 +15,7 @@ namespace Modelec
|
||||
{
|
||||
NONE,
|
||||
DEPLOY_BANNER,
|
||||
UNDEPLOY_BANNER,
|
||||
TAKE_POT,
|
||||
PLACE_POT,
|
||||
DEPLOY_MAX_SIZE,
|
||||
@@ -24,6 +25,7 @@ namespace Modelec
|
||||
{
|
||||
// Banner
|
||||
DEPLOY_BANNER_STEP,
|
||||
UNDEPLOY_BANNER_STEP,
|
||||
|
||||
// Take Pot
|
||||
ASC_GO_DOWN,
|
||||
@@ -56,6 +58,7 @@ namespace Modelec
|
||||
void Update();
|
||||
|
||||
void DeployBanner();
|
||||
void UndeployBanner();
|
||||
|
||||
void TakePot(bool two_floor = true);
|
||||
|
||||
|
||||
@@ -27,6 +27,8 @@ namespace Modelec
|
||||
{
|
||||
GO_TO_FRONT,
|
||||
DEPLOY_BANNER,
|
||||
WAIT_5_SECONDS,
|
||||
UNDEPLOY_BANNER,
|
||||
GO_FORWARD,
|
||||
DONE
|
||||
} step_;
|
||||
@@ -38,5 +40,7 @@ namespace Modelec
|
||||
rclcpp::Publisher<std_msgs::msg::Int64>::SharedPtr score_pub_;
|
||||
int mission_score_ = 0;
|
||||
Point spawn_;
|
||||
|
||||
rclcpp::Time deploy_time_;
|
||||
};
|
||||
}
|
||||
|
||||
@@ -113,6 +113,19 @@ namespace Modelec
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case UNDEPLOY_BANNER_STEP:
|
||||
{
|
||||
modelec_interfaces::msg::ActionServoPos msg;
|
||||
msg.id = 5;
|
||||
msg.pos = 0;
|
||||
servo_move_pub_->publish(msg);
|
||||
|
||||
step_running_ = 1;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case ASC_GO_DOWN:
|
||||
{
|
||||
modelec_interfaces::msg::ActionAscPos asc_msg;
|
||||
@@ -311,6 +324,20 @@ namespace Modelec
|
||||
}
|
||||
}
|
||||
|
||||
void ActionExecutor::UndeployBanner()
|
||||
{
|
||||
if (action_done_)
|
||||
{
|
||||
action_ = UNDEPLOY_BANNER;
|
||||
action_done_ = false;
|
||||
step_running_ = 0;
|
||||
|
||||
step_.push(UNDEPLOY_BANNER_STEP);
|
||||
|
||||
Update();
|
||||
}
|
||||
}
|
||||
|
||||
void ActionExecutor::TakePot(bool two_floor)
|
||||
{
|
||||
if (action_done_)
|
||||
|
||||
@@ -47,6 +47,7 @@ namespace Modelec
|
||||
case GO_TO_FRONT:
|
||||
{
|
||||
action_executor_->DeployBanner();
|
||||
deploy_time_ = node_->now();
|
||||
|
||||
step_ = DEPLOY_BANNER;
|
||||
}
|
||||
@@ -54,6 +55,28 @@ namespace Modelec
|
||||
break;
|
||||
|
||||
case DEPLOY_BANNER:
|
||||
{
|
||||
if ((node_->now() - deploy_time_).seconds() >= 5)
|
||||
{
|
||||
step_ = WAIT_5_SECONDS;
|
||||
}
|
||||
else
|
||||
{
|
||||
RCLCPP_INFO(node_->get_logger(), "Waiting for banner deployment to finish... %d seconds left", 5 - static_cast<int>((node_->now() - deploy_time_).seconds()));
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
case WAIT_5_SECONDS:
|
||||
{
|
||||
action_executor_->UndeployBanner();
|
||||
|
||||
step_ = UNDEPLOY_BANNER;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case UNDEPLOY_BANNER:
|
||||
{
|
||||
nav_->GoTo(spawn_.x, (nav_->GetPathfinding()->robot_length_mm_ / 2) + 600, M_PI_2, true, Pathfinding::FREE | Pathfinding::WALL | Pathfinding::OBSTACLE);
|
||||
|
||||
|
||||
@@ -5,8 +5,6 @@
|
||||
#include <sstream>
|
||||
|
||||
namespace Modelec {
|
||||
#define PI 3.14159265358979323846
|
||||
|
||||
std::vector<std::string> split(const std::string &s, char delim);
|
||||
|
||||
std::string join(const std::vector<std::string> &v, const std::string &delim);
|
||||
|
||||
Reference in New Issue
Block a user