map generating is optional
This commit is contained in:
parent
e9aa4e406d
commit
90f00a16ad
@ -24,6 +24,7 @@ rgb_camera_right:
|
|||||||
|
|
||||||
unity:
|
unity:
|
||||||
spawn_trees: true
|
spawn_trees: true
|
||||||
|
save_pointcloud: true # set to 'false' to save startup time, if visualization is not needed.
|
||||||
avg_tree_spacing: 4.0
|
avg_tree_spacing: 4.0
|
||||||
bounding_box: [80.0, 80.0, 11.0] # spawn objects within this bounding box
|
bounding_box: [80.0, 80.0, 11.0] # spawn objects within this bounding box
|
||||||
bounding_box_origin: [-10, 20, 2.5]
|
bounding_box_origin: [-10, 20, 2.5]
|
||||||
|
|||||||
@ -69,6 +69,8 @@ class FlightPilot {
|
|||||||
SceneID scene_id_{UnityScene::WAREHOUSE};
|
SceneID scene_id_{UnityScene::WAREHOUSE};
|
||||||
bool unity_ready_{false};
|
bool unity_ready_{false};
|
||||||
bool unity_render_{false};
|
bool unity_render_{false};
|
||||||
|
bool spawn_tree_{true};
|
||||||
|
bool save_pointcloud_{true};
|
||||||
RenderMessage_t unity_output_;
|
RenderMessage_t unity_output_;
|
||||||
uint16_t receive_id_{0};
|
uint16_t receive_id_{0};
|
||||||
FrameID frameID{0};
|
FrameID frameID{0};
|
||||||
|
|||||||
@ -44,6 +44,7 @@ FlightPilot::FlightPilot(const ros::NodeHandle& nh, const ros::NodeHandle& pnh)
|
|||||||
spawnTreesAndSavePointCloud();
|
spawnTreesAndSavePointCloud();
|
||||||
|
|
||||||
timer_main_loop_ = nh_.createTimer(ros::Rate(main_loop_freq_), &FlightPilot::mainLoopCallback, this);
|
timer_main_loop_ = nh_.createTimer(ros::Rate(main_loop_freq_), &FlightPilot::mainLoopCallback, this);
|
||||||
|
std::cout<<"[FlightRos] Ros Node is Ready!"<<std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
FlightPilot::~FlightPilot() { disconnectUnity(); }
|
FlightPilot::~FlightPilot() { disconnectUnity(); }
|
||||||
@ -153,11 +154,13 @@ bool FlightPilot::setUnity(const bool render) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool FlightPilot::spawnTreesAndSavePointCloud() {
|
bool FlightPilot::spawnTreesAndSavePointCloud() {
|
||||||
if (!unity_ready_ || unity_bridge_ptr_ == nullptr)
|
if (!unity_ready_ || unity_bridge_ptr_ == nullptr || !spawn_tree_)
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
unity_bridge_ptr_->spawnTrees(bounding_box_, bounding_box_origin_, avg_tree_spacing_);
|
unity_bridge_ptr_->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.
|
// 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.
|
// The following can be commented if evaluation is not needed.
|
||||||
Vector<3> min_corner = bounding_box_origin_ - 0.5 * bounding_box_;
|
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<bool>();
|
unity_render_ = cfg["unity_render"].as<bool>();
|
||||||
Scalar quad_size_i = cfg["quad_size"].as<Scalar>();
|
Scalar quad_size_i = cfg["quad_size"].as<Scalar>();
|
||||||
quad_size_ = Vector<3>(quad_size_i, quad_size_i, quad_size_i);
|
quad_size_ = Vector<3>(quad_size_i, quad_size_i, quad_size_i);
|
||||||
|
spawn_tree_ = cfg["unity"]["spawn_trees"].as<bool>();
|
||||||
|
save_pointcloud_ = cfg["unity"]["save_pointcloud"].as<bool>();
|
||||||
avg_tree_spacing_ = cfg["unity"]["avg_tree_spacing"].as<Scalar>();
|
avg_tree_spacing_ = cfg["unity"]["avg_tree_spacing"].as<Scalar>();
|
||||||
for (int i = 0; i < 3; ++i) {
|
for (int i = 0; i < 3; ++i) {
|
||||||
bounding_box_(i) = cfg["unity"]["bounding_box"][i].as<Scalar>();
|
bounding_box_(i) = cfg["unity"]["bounding_box"][i].as<Scalar>();
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user