ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

As stated in the octomap_msgs reference (http://docs.ros.org/melodic/api/octomap_msgs/html/namespaceoctomap__msgs.html#aebd9cf5ae6b6741b05e9f8dee383f410) , you have to free the memory after its use.

delete octree;

As stated in the octomap_msgs reference (http://docs.ros.org/melodic/api/octomap_msgs/html/namespaceoctomap__msgs.html#aebd9cf5ae6b6741b05e9f8dee383f410) , you have to free the memory after its use.

delete octree;

Edit:

In more details:

Simple Solution (not recommended if octomap is publishing map messages at some frequency) to get the idea across

void octomap_callback(const octomap_msgs::Octomap::ConstPtr& msg){
   ROS_INFO("Octomap resolution: [%f]", msg->resolution); 
   AbstractOcTree* tree = octomap_msgs::msgToMap(*msg); 
   OcTree* octree = dynamic_cast<OcTree*>(tree);
   ROS_INFO("Resolution of octree: [%f]" , octree->getResolution()); 
   // do some processing with octree
   delete octree;
}

To re-iterate the point about freeing the memory of each created octomap object, not just at the end of the program, please have look at the following code snippet.

Usual solution

ColorOcTree* octree = NULL;  // your global or class wide variable
std::mutex mutex_;    // a mutex to resolve the race conditions. 

void octomap_callback(const octomap_msgs::Octomap::ConstPtr& msg){
        octomap_msgs::Octomap received_msg = *msg; 
        AbstractOcTree* tree = octomap_msgs::fullMsgToMap(received_msg); 
        std::unique_lock<std::mutex> lock(mutex_); // lock the mutex
        if( octree != NULL )
            delete octree;
        octree = dynamic_cast<OcTree*>(tree);
}    


void process_octree(){
    std::unique_lock<std::mutex> lock(mutex_); // lock the mutex
    // process the octree_
    // then delete it
    delete octree_;
    octree_ = NULL;
}

As stated in the octomap_msgs reference (http://docs.ros.org/melodic/api/octomap_msgs/html/namespaceoctomap__msgs.html#aebd9cf5ae6b6741b05e9f8dee383f410) , you have to free the memory after its use.

delete octree;

Edit:

In more details:

Simple Solution (not recommended if octomap is publishing map messages at some frequency) to get the idea across

void octomap_callback(const octomap_msgs::Octomap::ConstPtr& msg){
   ROS_INFO("Octomap resolution: [%f]", msg->resolution); 
   AbstractOcTree* tree = octomap_msgs::msgToMap(*msg); 
   OcTree* octree = dynamic_cast<OcTree*>(tree);
   ROS_INFO("Resolution of octree: [%f]" , octree->getResolution()); 
   // do some processing with octree
   delete octree;
}

To re-iterate the point about freeing the memory of each created octomap object, not just at the end of the program, please have look at the following code snippet.

Usual solution

ColorOcTree* octree = NULL;  // your global or class wide variable
std::mutex mutex_;    // a mutex to resolve the race conditions. 

void octomap_callback(const octomap_msgs::Octomap::ConstPtr& msg){
        octomap_msgs::Octomap received_msg = *msg; 
        AbstractOcTree* tree = octomap_msgs::fullMsgToMap(received_msg); 
        std::unique_lock<std::mutex> lock(mutex_); // lock the mutex
        if( octree != NULL )
            delete octree;
)  // in-case we are receiving a new octomap before we processed the last one
            delete octree;      // so delete the previous stored object
        octree = dynamic_cast<OcTree*>(tree);
}    


void process_octree(){
    std::unique_lock<std::mutex> lock(mutex_); // lock the mutex
    // process the octree_
    // then delete it
    delete octree_;
    octree_ = NULL;
}