diff --git a/flightlib/configs/quadrotor_ros.yaml b/flightlib/configs/quadrotor_ros.yaml index ec9c838..dbb0db4 100644 --- a/flightlib/configs/quadrotor_ros.yaml +++ b/flightlib/configs/quadrotor_ros.yaml @@ -24,6 +24,7 @@ rgb_camera_right: unity: spawn_trees: true + save_pointcloud: true # set to 'false' to save startup time, if visualization is not needed. avg_tree_spacing: 4.0 bounding_box: [80.0, 80.0, 11.0] # spawn objects within this bounding box bounding_box_origin: [-10, 20, 2.5] diff --git a/flightlib/include/flightlib/ros_nodes/flight_pilot.hpp b/flightlib/include/flightlib/ros_nodes/flight_pilot.hpp index 9e673ab..48546bb 100644 --- a/flightlib/include/flightlib/ros_nodes/flight_pilot.hpp +++ b/flightlib/include/flightlib/ros_nodes/flight_pilot.hpp @@ -69,6 +69,8 @@ class FlightPilot { SceneID scene_id_{UnityScene::WAREHOUSE}; bool unity_ready_{false}; bool unity_render_{false}; + bool spawn_tree_{true}; + bool save_pointcloud_{true}; RenderMessage_t unity_output_; uint16_t receive_id_{0}; FrameID frameID{0}; diff --git a/flightlib/src/ros_nodes/flight_pilot.cpp b/flightlib/src/ros_nodes/flight_pilot.cpp index 95d6fa7..1045d50 100644 --- a/flightlib/src/ros_nodes/flight_pilot.cpp +++ b/flightlib/src/ros_nodes/flight_pilot.cpp @@ -44,6 +44,7 @@ FlightPilot::FlightPilot(const ros::NodeHandle& nh, const ros::NodeHandle& pnh) spawnTreesAndSavePointCloud(); timer_main_loop_ = nh_.createTimer(ros::Rate(main_loop_freq_), &FlightPilot::mainLoopCallback, this); + std::cout<<"[FlightRos] Ros Node is Ready!"<spawnTrees(bounding_box_, bounding_box_origin_, avg_tree_spacing_); + if (!save_pointcloud_) + return true; // Saving point cloud during the testing is much time-consuming, but can be used for evaluation. // The following can be commented if evaluation is not needed. Vector<3> min_corner = bounding_box_origin_ - 0.5 * bounding_box_; @@ -195,6 +198,8 @@ bool FlightPilot::loadParams(const YAML::Node& cfg) { unity_render_ = cfg["unity_render"].as(); Scalar quad_size_i = cfg["quad_size"].as(); quad_size_ = Vector<3>(quad_size_i, quad_size_i, quad_size_i); + spawn_tree_ = cfg["unity"]["spawn_trees"].as(); + save_pointcloud_ = cfg["unity"]["save_pointcloud"].as(); avg_tree_spacing_ = cfg["unity"]["avg_tree_spacing"].as(); for (int i = 0; i < 3; ++i) { bounding_box_(i) = cfg["unity"]["bounding_box"][i].as();