Fix small bugs with MATLAB wrapping

release/4.3a0
dellaert 2016-01-27 09:24:49 -08:00
parent f078741ed4
commit 88fad4caff
3 changed files with 7 additions and 7 deletions

10
gtsam.h
View File

@ -434,11 +434,11 @@ class Rot3 {
static gtsam::Rot3 Rz(double t);
static gtsam::Rot3 RzRyRx(double x, double y, double z);
static gtsam::Rot3 RzRyRx(Vector xyz);
static gtsam::Rot3 yaw(double t); // positive yaw is to right (as in aircraft heading)
static gtsam::Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude)
static gtsam::Rot3 roll(double t); // positive roll is to right (increasing yaw in aircraft)
static gtsam::Rot3 ypr(double y, double p, double r);
static gtsam::Rot3 quaternion(double w, double x, double y, double z);
static gtsam::Rot3 Yaw(double t); // positive yaw is to right (as in aircraft heading)
static gtsam::Rot3 Pitch(double t); // positive pitch is up (increasing aircraft altitude)
static gtsam::Rot3 Roll(double t); // positive roll is to right (increasing yaw in aircraft)
static gtsam::Rot3 Ypr(double y, double p, double r);
static gtsam::Rot3 Quaternion(double w, double x, double y, double z);
static gtsam::Rot3 Rodrigues(Vector v);
// Testable

View File

@ -19,6 +19,7 @@
#pragma once
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/geometry/Pose2.h>
#include <gtsam/slam/TriangulationFactor.h>
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>

View File

@ -31,8 +31,7 @@ struct Range;
* Works for any two types A1,A2 for which the functor Range<A1,A2>() is defined
* @addtogroup SAM
*/
template <typename A1, typename A2 = A1,
typename T = typename Range<A1, A2>::result_type>
template <typename A1, typename A2 = A1, typename T = double>
class RangeFactor : public ExpressionFactor2<T, A1, A2> {
private:
typedef RangeFactor<A1, A2> This;