BearingRangeFactor2D constructor crashes in the matlab wrapper

Issue #306 closed
Simon Julier created an issue

The constructor of BearingRangeFactor in the matlab wrapper unwraps an argument with the wrong type. Therefore, any attempt to construct this factor will always cause matlab to crash. As a result, the testPlanarSLAMExample example will fail. As mentioned in one of my previous posts, we intend to use GTSAM for teaching and having the 2D example working for us in Matlab is extremely important.

The constructor for BearingRangeFactor takes a constant reference to the range:

  /// primary constructor
  BearingRangeFactor(Key key1, Key key2, const B& measuredBearing,
                     const R& measuredRange, const SharedNoiseModel& model)
      : Base(key1, key2, model, T(measuredBearing, measuredRange)) {
    this->initialize(expression(key1, key2));
  }

The matlab wrapper interprets this as a reference to a type, and generates the following unwrapping code:

  double& measuredRange = *unwrap_shared_ptr< double >(in[3], "ptr_double");

However, the unwrapping doesn't work on scalar types. If passed by value, the wrapper function should be:

  double measuredRange = unwrap< double >(in[3]);

Other factors - such as RangeFactor - are constructed by passing the range measurement in by value and so do not have these problems here.

What is the right approach here? Should the BearingRangeFactor constructor be passed by value? This would fix this bug, but means that there is still a bug in the wrapper code itself. Should scalar values passed by const types be turned into pass-by-value? Should scalar values passed by reference be return as a pointer to an array?

Comments (6)

  1. Simon Julier reporter

    Just wanted to confirm. We had discussed two options here:

    1. Changing the constructor for the BearingRangeFactor to just take a double, like the RangeFactor
    2. Modifying the wrapper to take a const scalar reference and pass by value.

    Which option do we want? To me the second seems better (because it fixes a more general bug which could turn up and leaves whatever the intention for the range in place).

    Cheers,

    Simon

  2. Simon Julier reporter

    I've done a modification in the fix/matlab_wrapper_scalar_references. This just changes Arguments to check for scalar types.

    The code will not crash with constant or non constant references. However, for non const references the result won't be fed back - I haven't figured out how to update the out[.] arguments.

    PlanarSLAMExample now seems to crash because of an issue with printing. I'm using #303 to check this.

  3. Log in to comment