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

Using octomap::OcTree as a type in a vector

asked 2014-06-04 07:01:56 -0500

updated 2014-06-04 07:20:52 -0500

Hi,

I'm trying to implement a 3D SLAM algorithm based on octomap, however, my particle class which contains an octree as the map, cannot be resized or pushed onto a vector of particles. My class construct for the particles is:

struct SLAMParticle
{
    SLAMParticle():m_octree(0.05){

    }
    octomap::OcTree m_octree;
    double weight;
    tf::Pose pose;
};

typedef std::vector<SLAMParticle> SLAMParticles;

I get an error when building that seems to be due to the lack of a default constructor, for movement and copying. For example there is no definition of an &operator= for octree, to transfer data between two octrees.

The error is:

/opt/ros/hydro/include/octomap/OcTreeBaseImpl.h:468:37: error: ‘octomap::OcTreeBaseImpl<NODE, INTERFACE>& octomap::OcTreeBaseImpl<NODE, INTERFACE>::operator=(const octomap::OcTreeBaseImpl<NODE, INTERFACE>&)  [with NODE = octomap::OcTreeNode, INTERFACE = octomap::AbstractOccupancyOcTree]’ is private
/opt/ros/hydro/include/octomap/OccupancyOcTreeBase.h:69:9: error: within this context

and seems to relate to a point in the code where the SLAMParticles type is resized.

So my question is, is this a problem with using octomap::OcTree and that it is not designed to work within a vector structure or is it due to some other issue. If it is some other issue, can I just create a default constructor or &operator= for OcTree and its parent OccupancyOcTreeBase for use in vectors and general assignments?

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2014-06-04 10:16:20 -0500

AHornung gravatar image

There is no default constructor because a tree requires a fixed resolution during initialization, it is not possible to construct an octree without.

The assignment operator was made private on purpose, to discourage unintended shallow copy operations (with nasty side-effect, since the nodes live on the heap). You can perform a deep copy (expensive!) with the copy constructor. If you want to store octrees in a container, best create them once and put pointers to them (regular or smart) into the container or your struct.

By the way, best check the OctoMap API documentation for reference (and the OctoMap mailing list for in-depth discussions related to OctoMap).

edit flag offensive delete link more

Comments

but can you clear up for me, to achieve a copy operation or =operator, apart from changing resolution, is this best achieved by a clear() method, followed by a swapContent() call? I note that the swap content simply changes the pointer location not the underlying data.

PeterMilani gravatar image PeterMilani  ( 2014-06-09 07:44:17 -0500 )edit
1

To answer my above query the answer is no. To achieve copying its best to conduct deep copy as per the recursive copy in the OcTreeBaseImpl initialiser. Copying is required for the resampling of particle maps. Additionally deriving a map class from OcTreeBaseImpl gives more freedom in implementation

PeterMilani gravatar image PeterMilani  ( 2014-06-10 18:20:45 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-06-04 07:01:56 -0500

Seen: 644 times

Last updated: Jun 04 '14