@@ -48,7 +48,11 @@ void AutowarePathWithLaneIdDisplay::preProcessMessageDetail()
4848AutowarePathWithLaneIdDisplay::~AutowarePathWithLaneIdDisplay ()
4949{
5050 for (const auto & e : lane_id_obj_ptrs_) {
51- scene_node_->removeChild (e.first .get ());
51+ auto node_ptr = e.first ;
52+ node_ptr->detachAllObjects ();
53+ node_ptr->removeAndDestroyAllChildren ();
54+ scene_node_->removeChild (node_ptr);
55+ scene_manager_->destroySceneNode (node_ptr);
5256 }
5357 lane_id_obj_ptrs_.clear ();
5458 lane_id_obj_ptrs_.shrink_to_fit ();
@@ -58,21 +62,31 @@ void AutowarePathWithLaneIdDisplay::preVisualizePathFootprintDetail(
5862 const autoware_internal_planning_msgs::msg::PathWithLaneId::ConstSharedPtr msg_ptr)
5963{
6064 const size_t size = msg_ptr->points .size ();
61- // clear previous text
62- for (const auto & [node_ptr, text_ptr] : lane_id_obj_ptrs_) {
63- scene_node_-> removeChild (node_ptr. get () );
65+
66+ for (auto & e : lane_id_obj_ptrs_) {
67+ e. second -> setVisible ( false );
6468 }
65- lane_id_obj_ptrs_.clear ();
66- for (std::size_t i = 0 ; i < size; i++) {
67- std::unique_ptr<Ogre::SceneNode> node_ptr;
68- node_ptr.reset (scene_node_->createChildSceneNode ());
69- auto text_ptr =
70- std::make_unique<rviz_rendering::MovableText>(" not initialized" , " Liberation Sans" , 0.1 );
71- text_ptr->setVisible (false );
72- text_ptr->setTextAlignment (
73- rviz_rendering::MovableText::H_CENTER, rviz_rendering::MovableText::V_ABOVE);
74- node_ptr->attachObject (text_ptr.get ());
75- lane_id_obj_ptrs_.push_back (std::make_pair (std::move (node_ptr), std::move (text_ptr)));
69+ if (size > lane_id_obj_ptrs_.size ()) {
70+ for (size_t i = lane_id_obj_ptrs_.size (); i < size; i++) {
71+ auto node_ptr = scene_node_->createChildSceneNode ();
72+ auto text_ptr =
73+ std::make_unique<rviz_rendering::MovableText>(" not initialized" , " Liberation Sans" , 0.1 );
74+ text_ptr->setVisible (false );
75+ text_ptr->setTextAlignment (
76+ rviz_rendering::MovableText::H_CENTER, rviz_rendering::MovableText::V_ABOVE);
77+ node_ptr->attachObject (text_ptr.get ());
78+ lane_id_obj_ptrs_.emplace_back (node_ptr, std::move (text_ptr));
79+ }
80+ } else if (size < lane_id_obj_ptrs_.size ()) {
81+ // Remove excess objects from scene and vector
82+ for (size_t i = size; i < lane_id_obj_ptrs_.size (); i++) {
83+ auto & node_ptr = lane_id_obj_ptrs_[i].first ;
84+ node_ptr->detachAllObjects ();
85+ node_ptr->removeAndDestroyAllChildren ();
86+ scene_node_->removeChild (node_ptr);
87+ scene_manager_->destroySceneNode (node_ptr);
88+ }
89+ lane_id_obj_ptrs_.resize (size);
7690 }
7791}
7892
0 commit comments