start lidar

This commit is contained in:
acki
2025-10-14 21:00:53 +02:00
parent 58db2215c9
commit a7bf2d3a2e
5 changed files with 25 additions and 2 deletions

View File

@@ -43,6 +43,8 @@ namespace ModelecGUI
void AskMap();
void StartLidar();
protected:
void paintEvent(QPaintEvent*) override;
@@ -87,6 +89,8 @@ namespace ModelecGUI
rclcpp::Subscription<modelec_interfaces::msg::Obstacle>::SharedPtr obstacle_removed_sub_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr ask_map_obstacle_client_;
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr start_lidar_pub_;
modelec_interfaces::msg::OdometryPos enemy_pos_;
bool hasEnemy = false;
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr enemy_pos_pub_;

View File

@@ -88,6 +88,7 @@ namespace ModelecGUI {
connect(map_action_, &QAction::triggered, this, [this]() {
stackedWidget->setCurrentWidget(test_map_page_);
test_map_page_->StartLidar();
});
connect(playmat_map_, &QAction::triggered, this, [this]() {

View File

@@ -137,6 +137,8 @@ namespace ModelecGUI
auto result2 = ask_map_obstacle_client_->async_send_request(std::make_shared<std_srvs::srv::Empty::Request>());
rclcpp::spin_until_future_complete(node_->get_node_base_interface(), result2);
start_lidar_pub_ = node_->create_publisher<std_msgs::msg::Bool>("lidar/start", 10);
}
void TestMapPage::setPlaymatGrid()
@@ -161,6 +163,12 @@ namespace ModelecGUI
ask_map_obstacle_client_->async_send_request(std::make_shared<std_srvs::srv::Empty::Request>());
}
void TestMapPage::StartLidar() {
auto msg = std_msgs::msg::Bool();
msg.data = true;
start_lidar_pub_->publish(msg);
}
void TestMapPage::paintEvent(QPaintEvent* paint_event)
{
QWidget::paintEvent(paint_event);

View File

@@ -5,6 +5,7 @@
#include <modelec_interfaces/msg/odometry_pos.hpp>
#include <modelec_interfaces/msg/strat_state.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <std_msgs/msg/bool.hpp>
namespace Modelec
{
@@ -27,6 +28,7 @@ namespace Modelec
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr enemy_pos_pub_;
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr close_enemy_pos_pub_;
rclcpp::Publisher<modelec_interfaces::msg::OdometryPos>::SharedPtr enemy_long_time_pub_;
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr start_sub_;
rclcpp::TimerBase::SharedPtr timer_;

View File

@@ -71,6 +71,14 @@ namespace Modelec
enemy_long_time_pub_ = this->create_publisher<modelec_interfaces::msg::OdometryPos>(
"/enemy/long_time", 10);
start_sub_ = this->create_subscription<std_msgs::msg::Bool>(
"/lidar/start", 10,
[this](const std_msgs::msg::Bool::SharedPtr msg)
{
game_stated_ = msg->data;
RCLCPP_INFO(this->get_logger(), "Game started state changed: %s", game_stated_ ? "true" : "false");
});
timer_ = this->create_wall_timer(
std::chrono::nanoseconds(static_cast<int>(refresh_rate_s_ )),
[this]()
@@ -89,11 +97,11 @@ namespace Modelec
void EnemyManager::OnLidarData(const sensor_msgs::msg::LaserScan::SharedPtr msg)
{
/*if (!game_stated_)
if (!game_stated_)
{
RCLCPP_INFO(this->get_logger(), "Game not started, ignoring Lidar data");
return;
}*/
}
is_enemy_close_ = false;