Skip to content

Commit

Permalink
Added and tested drone position update and network update detection
Browse files Browse the repository at this point in the history
  • Loading branch information
guillermogilg99 committed Oct 7, 2024
1 parent 1e8ca8f commit f2d696d
Showing 1 changed file with 33 additions and 3 deletions.
36 changes: 33 additions & 3 deletions src/ROS/local_planner_ros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <heuristic_planners/CoordinateList.h>



/**
* @brief Demo Class that demonstrate how to use the algorithms classes and utils
* with ROS
Expand All @@ -65,10 +66,10 @@ class HeuristicLocalPlannerROS
path_local_sub_ = lnh_.subscribe<heuristic_planners::CoordinateList>("/planner_ros_node/global_path", 1, &HeuristicLocalPlannerROS::globalPathCallback, this);

//GLOBAL POSITIONING SUBSCRIBER - for SDF query
// globalposition_local_sub_ = lnh_.subscribe<geometry_msgs::PoseStamped>("/ground_truth_to_tf/pose", 1, &HeuristicLocalPlannerROS::globalPositionCallback, this);
globalposition_local_sub_ = lnh_.subscribe<geometry_msgs::PoseStamped>("/ground_truth_to_tf/pose", 1, &HeuristicLocalPlannerROS::globalPositionCallback, this);
// pointcloud_local_sub_ = lnh_.subscribe("/points", 1, &HeuristicLocalPlannerROS::pointCloudCallback, this); //compile
occupancy_grid_local_sub_ = lnh_.subscribe<nav_msgs::OccupancyGrid>("/grid", 1, &HeuristicLocalPlannerROS::occupancyGridCallback, this);
//network_update_sub_ = lnh_.subscribe<std_msgs::Empty>("/net_update", 1, &HeuristicLocalPlannerROS::networkUpdateCallback, this);
network_update_sub_ = lnh_.subscribe<std_msgs::Empty>("/net_update", 1, &HeuristicLocalPlannerROS::networkUpdateCallback, this);

// request_path_server_ = lnh_.advertiseService("request_path", &HeuristicLocalPlannerROS::requestPathService, this); // This is in planner_ros_node.cpp and the corresponding service defined.
change_planner_server_ = lnh_.advertiseService("set_algorithm", &HeuristicLocalPlannerROS::setAlgorithm, this);
Expand All @@ -77,7 +78,7 @@ class HeuristicLocalPlannerROS
point_markers_pub_ = lnh_.advertise<visualization_msgs::Marker>("path_points_markers", 1);
cloud_test = lnh_.advertise<pcl::PointCloud<pcl::PointXYZ> >("/cloud_PCL", 1, true); // Defined by me to show the point cloud as pcl::PointCloud<pcl::PointXYZ

//networkReceivedFlag_ = 1;
networkReceivedFlag_ = 1;
globalPathReceived_ = 0;
timed_local_path_ = lnh_.createTimer(ros::Duration(1), &HeuristicLocalPlannerROS::localtimedCallback, this);
}
Expand Down Expand Up @@ -126,6 +127,22 @@ class HeuristicLocalPlannerROS

}

void networkUpdateCallback(const std_msgs::Empty::ConstPtr& msg){
ROS_INFO("Received new network callback");
networkReceivedFlag_ = 1;
}

void globalPositionCallback(const geometry_msgs::PoseStamped::ConstPtr& msg){
double drone_x = resolution_ * std::round(msg->pose.position.x / resolution_);
double drone_y = resolution_ * std::round(msg->pose.position.y / resolution_);
double drone_z = resolution_ * std::round(msg->pose.position.z / resolution_);

// Store as class members
this->drone_x_ = drone_x;
this->drone_y_ = drone_y;
this->drone_z_ = drone_z;
}

void localtimedCallback(const ros::TimerEvent& event)
{
std::cout << "-----TIMED CALLBACK------" << std::endl;
Expand Down Expand Up @@ -581,10 +598,23 @@ class HeuristicLocalPlannerROS
int number_of_points;
bool mapReceived;

// --------NEW VARIABLES -- SIREN LOCAL PLANNER
//drone global position
double drone_x_ = 0.0;
double drone_y_ = 0.0;
double drone_z_ = 0.0;

//global path variable and flag
Planners::utils::CoordinateList global_path_;
int globalPathReceived_;

//Network Flag and subscriber
int networkReceivedFlag_;
ros::Subscriber network_update_sub_;

//Global position subscriber
ros::Subscriber globalposition_local_sub_;


// local pathplanner loop timer
ros::Timer timed_local_path_;
Expand Down

0 comments on commit f2d696d

Please sign in to comment.