|
| 1 | +#include <rclcpp/rclcpp.hpp> |
| 2 | +#include <std_msgs/msg/header.hpp> |
| 3 | +#include <unique_identifier_msgs/msg/uuid.hpp> |
| 4 | +#include <geometry_msgs/msg/point.hpp> |
| 5 | +#include <geometry_msgs/msg/vector3.hpp> |
| 6 | +#include <visualization_msgs/msg/marker_array.hpp> |
| 7 | +#include "nav2_dynamic_msgs/msg/obstacle.hpp" |
| 8 | +#include "nav2_dynamic_msgs/msg/obstacle_array.hpp" |
| 9 | + |
| 10 | +#include <random> |
| 11 | +#include <vector> |
| 12 | +#include <cmath> |
| 13 | + |
| 14 | +class ObstacleTracker : public rclcpp::Node { |
| 15 | +public: |
| 16 | + ObstacleTracker() : Node("obstacle_tracker") { |
| 17 | + publisher_ = this->create_publisher<nav2_dynamic_msgs::msg::ObstacleArray>("/tracked_obstacles", 10); |
| 18 | + marker_publisher_ = this->create_publisher<visualization_msgs::msg::MarkerArray>("/obstacle_markers", 10); |
| 19 | + |
| 20 | + timer_ = this->create_wall_timer(std::chrono::milliseconds(100), |
| 21 | + std::bind(&ObstacleTracker::update_obstacles, this)); |
| 22 | + initialize_waypoints(); |
| 23 | + initialize_obstacles(); |
| 24 | + } |
| 25 | + |
| 26 | +private: |
| 27 | + rclcpp::Publisher<nav2_dynamic_msgs::msg::ObstacleArray>::SharedPtr publisher_; |
| 28 | + rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr marker_publisher_; |
| 29 | + rclcpp::TimerBase::SharedPtr timer_; |
| 30 | + std::vector<nav2_dynamic_msgs::msg::Obstacle> obstacles_; |
| 31 | + std::vector<std::vector<geometry_msgs::msg::Point>> waypoints_; |
| 32 | + std::vector<size_t> waypoint_indices_; |
| 33 | + std::vector<double> progresses_; |
| 34 | + |
| 35 | + void initialize_waypoints() { |
| 36 | + std::random_device rd; |
| 37 | + std::mt19937 gen(rd()); |
| 38 | + std::uniform_real_distribution<float> pos_dist(-10.0, 10.0); |
| 39 | + |
| 40 | + waypoints_.resize(4); |
| 41 | + waypoint_indices_.resize(4, 0); |
| 42 | + progresses_.resize(4, 0.0); |
| 43 | + |
| 44 | + for (int i = 0; i < 4; ++i) { |
| 45 | + for (int j = 0; j < 5; ++j) { |
| 46 | + geometry_msgs::msg::Point p; |
| 47 | + p.x = pos_dist(gen); |
| 48 | + p.y = pos_dist(gen); |
| 49 | + p.z = 0.0; |
| 50 | + waypoints_[i].push_back(p); |
| 51 | + } |
| 52 | + } |
| 53 | + } |
| 54 | + |
| 55 | + void initialize_obstacles() { |
| 56 | + std::random_device rd; |
| 57 | + std::mt19937 gen(rd()); |
| 58 | + std::uniform_real_distribution<float> pos_dist(-10.0, 10.0); |
| 59 | + |
| 60 | + for (int i = 0; i < 4; ++i) { |
| 61 | + nav2_dynamic_msgs::msg::Obstacle obs; |
| 62 | + obs.uuid = generate_uuid(); |
| 63 | + obs.score = 1.0; |
| 64 | + obs.position = waypoints_[i][0]; |
| 65 | + obs.velocity.x = 0.0; |
| 66 | + obs.velocity.y = 0.0; |
| 67 | + obs.velocity.z = 0.0; |
| 68 | + obs.size.x = 1.0; |
| 69 | + obs.size.y = 1.0; |
| 70 | + obs.size.z = 1.0; |
| 71 | + std::fill(std::begin(obs.position_covariance), std::end(obs.position_covariance), 0.1); |
| 72 | + std::fill(std::begin(obs.velocity_covariance), std::end(obs.velocity_covariance), 0.05); |
| 73 | + |
| 74 | + obstacles_.push_back(obs); |
| 75 | + } |
| 76 | + } |
| 77 | + |
| 78 | + unique_identifier_msgs::msg::UUID generate_uuid() { |
| 79 | + unique_identifier_msgs::msg::UUID uuid; |
| 80 | + std::random_device rd; |
| 81 | + for (auto &byte : uuid.uuid) { |
| 82 | + byte = static_cast<uint8_t>(rd()); |
| 83 | + } |
| 84 | + return uuid; |
| 85 | + } |
| 86 | + |
| 87 | + void update_obstacles() { |
| 88 | + if (obstacles_.empty() || waypoints_.empty()) return; |
| 89 | + |
| 90 | + nav2_dynamic_msgs::msg::ObstacleArray msg; |
| 91 | + msg.header.stamp = this->now(); |
| 92 | + msg.header.frame_id = "map"; |
| 93 | + |
| 94 | + visualization_msgs::msg::MarkerArray marker_array; |
| 95 | + int id = 0; |
| 96 | + |
| 97 | + for (size_t i = 0; i < obstacles_.size(); ++i) { |
| 98 | + geometry_msgs::msg::Point start = waypoints_[i][waypoint_indices_[i]]; |
| 99 | + geometry_msgs::msg::Point end = waypoints_[i][(waypoint_indices_[i] + 1) % waypoints_[i].size()]; |
| 100 | + |
| 101 | + progresses_[i] += 0.02; // Adjust speed of movement |
| 102 | + if (progresses_[i] >= 1.0) { |
| 103 | + progresses_[i] = 0.0; |
| 104 | + waypoint_indices_[i] = (waypoint_indices_[i] + 1) % waypoints_[i].size(); |
| 105 | + } |
| 106 | + |
| 107 | + obstacles_[i].position.x = start.x + (end.x - start.x) * progresses_[i]; |
| 108 | + obstacles_[i].position.y = start.y + (end.y - start.y) * progresses_[i]; |
| 109 | + |
| 110 | + visualization_msgs::msg::Marker marker; |
| 111 | + marker.header.frame_id = "map"; |
| 112 | + marker.header.stamp = this->now(); |
| 113 | + marker.ns = "obstacles"; |
| 114 | + marker.id = id++; |
| 115 | + marker.type = visualization_msgs::msg::Marker::SPHERE; |
| 116 | + marker.action = visualization_msgs::msg::Marker::ADD; |
| 117 | + marker.pose.position = obstacles_[i].position; |
| 118 | + marker.scale.x = obstacles_[i].size.x; |
| 119 | + marker.scale.y = obstacles_[i].size.y; |
| 120 | + marker.scale.z = obstacles_[i].size.z; |
| 121 | + marker.color.a = 1.0; |
| 122 | + marker.color.r = 1.0; |
| 123 | + marker.color.g = 0.0; |
| 124 | + marker.color.b = 0.0; |
| 125 | + marker_array.markers.push_back(marker); |
| 126 | + } |
| 127 | + |
| 128 | + msg.obstacles = obstacles_; |
| 129 | + publisher_->publish(msg); |
| 130 | + marker_publisher_->publish(marker_array); |
| 131 | + } |
| 132 | +}; |
| 133 | + |
| 134 | +int main(int argc, char **argv) { |
| 135 | + rclcpp::init(argc, argv); |
| 136 | + rclcpp::spin(std::make_shared<ObstacleTracker>()); |
| 137 | + rclcpp::shutdown(); |
| 138 | + return 0; |
| 139 | +} |
0 commit comments