first version ever compiled.
... Not without some changes: - add traits<size_t> in Key.h - add these to JacobianFactor: explicit JacobianFactor(const Eigen::Map<Vector>& b_in); Vector py_getb() { return getb(); } Matrix py_getA() { return getA(); } --------- ... Remaining corner cases: ☐ Eigency: Map[] to Block ☐ Eigency: ambiguous call: A(const T&) A(const Vector& v) and Eigency A(Map[Vector]& v) ☐ Fix return properly ☐ handle pair ☐ Fix method template of Vector/Matrix: template argument is [Vector] while arugment is Map[Vector] ☐ Constructor: generate default constructor? (hack: if it's serializable?) ☐ Constructor: ambiguous construct from Vector/Matrix ☐ Key and size_t: traits<size_t> doesn't exist ☐ [Nice to have] Auto delete duplicate methods in derived classrelease/4.3a0
parent
3352aed2f7
commit
948e6262db
|
@ -100,7 +100,7 @@ void Argument::proxy_check(FileWriter& proxyFile, const string& s) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Argument::emit_cython_pxd(FileWriter& file) const {
|
void Argument::emit_cython_pxd(FileWriter& file) const {
|
||||||
string typeName = type.qualifiedName("_");
|
string typeName = type.cythonClassName();
|
||||||
string cythonType = typeName;
|
string cythonType = typeName;
|
||||||
if (type.isEigen()) {
|
if (type.isEigen()) {
|
||||||
cythonType = "Map[" + typeName + "Xd]&";
|
cythonType = "Map[" + typeName + "Xd]&";
|
||||||
|
|
|
@ -686,7 +686,7 @@ void Class::emit_cython_pxd(FileWriter& pxdFile) const {
|
||||||
}
|
}
|
||||||
pxdFile.oss << "]";
|
pxdFile.oss << "]";
|
||||||
}
|
}
|
||||||
if (parentClass) pxdFile.oss << "(" << parentClass->qualifiedName("_") << ")";
|
if (parentClass) pxdFile.oss << "(" << parentClass->cythonClassName() << ")";
|
||||||
pxdFile.oss << ":\n";
|
pxdFile.oss << ":\n";
|
||||||
|
|
||||||
constructor.emit_cython_pxd(pxdFile, cythonClassName());
|
constructor.emit_cython_pxd(pxdFile, cythonClassName());
|
||||||
|
@ -741,7 +741,10 @@ void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector<Class>& allCl
|
||||||
// __cinit___
|
// __cinit___
|
||||||
pyxFile.oss << "\tdef __cinit__(self):\n"
|
pyxFile.oss << "\tdef __cinit__(self):\n"
|
||||||
"\t\tself." << pyxCythonObj() << " = "
|
"\t\tself." << pyxCythonObj() << " = "
|
||||||
<< pyxSharedCythonClass() << "(new " << pyxCythonClass() << "())\n";
|
<< pyxSharedCythonClass() << "(";
|
||||||
|
if (constructor.hasDefaultConstructor())
|
||||||
|
pyxFile.oss << "new " << pyxCythonClass() << "()";
|
||||||
|
pyxFile.oss << ")\n";
|
||||||
pyxInitParentObj(pyxFile, "\t\tself", "self." + pyxCythonObj(), allClasses);
|
pyxInitParentObj(pyxFile, "\t\tself", "self." + pyxCythonObj(), allClasses);
|
||||||
|
|
||||||
// cyCreateFromShared
|
// cyCreateFromShared
|
||||||
|
@ -753,6 +756,11 @@ void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector<Class>& allCl
|
||||||
pyxInitParentObj(pyxFile, "\t\tret", "other", allClasses);
|
pyxInitParentObj(pyxFile, "\t\tret", "other", allClasses);
|
||||||
pyxFile.oss << "\t\treturn ret" << "\n";
|
pyxFile.oss << "\t\treturn ret" << "\n";
|
||||||
|
|
||||||
|
// Generate cyCreateFromValue by default, although for some classes it can't be used
|
||||||
|
// It's only usable if its copy constructor AND its copy assignment operator exist
|
||||||
|
// Copy assignment operator is needed because Cython might assign the obj to its temp variable.
|
||||||
|
// Some class (e.g. noiseModel::Robust) have copy constructor but no copy assignment operator
|
||||||
|
if (constructor.nrOverloads() >= 1) {
|
||||||
// cyCreateFromValue
|
// cyCreateFromValue
|
||||||
pyxFile.oss << "\t@staticmethod\n";
|
pyxFile.oss << "\t@staticmethod\n";
|
||||||
pyxFile.oss << "\tcdef " << pythonClassName() << " cyCreateFromValue(const "
|
pyxFile.oss << "\tcdef " << pythonClassName() << " cyCreateFromValue(const "
|
||||||
|
@ -764,6 +772,7 @@ void Class::emit_cython_pyx(FileWriter& pyxFile, const std::vector<Class>& allCl
|
||||||
pyxInitParentObj(pyxFile, "\t\tret", "ret." + pyxCythonObj(), allClasses);
|
pyxInitParentObj(pyxFile, "\t\tret", "ret." + pyxCythonObj(), allClasses);
|
||||||
pyxFile.oss << "\t\treturn ret" << "\n";
|
pyxFile.oss << "\t\treturn ret" << "\n";
|
||||||
pyxFile.oss << "\n";
|
pyxFile.oss << "\n";
|
||||||
|
}
|
||||||
|
|
||||||
// Constructors
|
// Constructors
|
||||||
constructor.emit_cython_pyx(pyxFile, *this);
|
constructor.emit_cython_pyx(pyxFile, *this);
|
||||||
|
|
|
@ -160,10 +160,17 @@ void Constructor::emit_cython_pyx(FileWriter& pyxFile, const Class& cls) const {
|
||||||
<< ((i > 0) ? to_string(i) : "") << "__(";
|
<< ((i > 0) ? to_string(i) : "") << "__(";
|
||||||
args.emit_cython_pyx(pyxFile);
|
args.emit_cython_pyx(pyxFile);
|
||||||
pyxFile.oss << "): \n";
|
pyxFile.oss << "): \n";
|
||||||
|
|
||||||
|
// Don't use cyCreateFromValue because the class might not have
|
||||||
|
// copy constructor and copy assignment operator!!
|
||||||
|
// For example: noiseModel::Robust doesn't have the copy assignment operator
|
||||||
|
// because its members are shared_ptr to abstract base classes. That fails
|
||||||
|
// Cython to generate the object as it assigns the new obj to a temp variable.
|
||||||
pyxFile.oss << "\t\treturn " << cls.cythonClassName()
|
pyxFile.oss << "\t\treturn " << cls.cythonClassName()
|
||||||
<< ".cyCreateFromValue(" << cls.pyxCythonClass() << "(";
|
<< ".cyCreateFromShared(" << cls.pyxSharedCythonClass()
|
||||||
|
<< "(new " << cls.pyxCythonClass() << "(";
|
||||||
args.emit_cython_pyx_asParams(pyxFile);
|
args.emit_cython_pyx_asParams(pyxFile);
|
||||||
pyxFile.oss << ")"
|
pyxFile.oss << "))"
|
||||||
<< ")\n";
|
<< ")\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -81,7 +81,7 @@ void Method::emit_cython_pxd(FileWriter& file) const {
|
||||||
for(size_t i = 0; i < nrOverloads(); ++i) {
|
for(size_t i = 0; i < nrOverloads(); ++i) {
|
||||||
file.oss << "\t\t";
|
file.oss << "\t\t";
|
||||||
returnVals_[i].emit_cython_pxd(file);
|
returnVals_[i].emit_cython_pxd(file);
|
||||||
file.oss << name_ << "(";
|
file.oss << ((name_ == "print") ? "_print \"print\"" : name_) << "(";
|
||||||
argumentList(i).emit_cython_pxd(file);
|
argumentList(i).emit_cython_pxd(file);
|
||||||
file.oss << ")";
|
file.oss << ")";
|
||||||
if (is_const_) file.oss << " const";
|
if (is_const_) file.oss << " const";
|
||||||
|
@ -93,11 +93,17 @@ void Method::emit_cython_pxd(FileWriter& file) const {
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
string funcName = ((name_ == "print") ? "_print" : name_);
|
string funcName = ((name_ == "print") ? "_print" : name_);
|
||||||
// don't support overloads for static method :-(
|
|
||||||
size_t N = nrOverloads();
|
size_t N = nrOverloads();
|
||||||
for(size_t i = 0; i < N; ++i) {
|
for(size_t i = 0; i < N; ++i) {
|
||||||
file.oss << "\tdef " << funcName;
|
file.oss << "\tdef " << funcName;
|
||||||
|
// modify name of function instantiation as python doesn't allow overloads
|
||||||
|
// e.g. template<T={A,B,C}> funcName(...) --> funcNameA, funcNameB, funcNameC
|
||||||
|
// TODO: handle overloading properly!! This is lazy...
|
||||||
if (templateArgValue_) file.oss << templateArgValue_->name();
|
if (templateArgValue_) file.oss << templateArgValue_->name();
|
||||||
|
// change function overload's name: funcName(...) --> funcName_1, funcName_2
|
||||||
|
// TODO: handle overloading properly!! This is lazy...
|
||||||
|
file.oss << ((i>0)? "_" + to_string(i):"");
|
||||||
|
// funtion arguments
|
||||||
file.oss << "(self";
|
file.oss << "(self";
|
||||||
if (argumentList(i).size() > 0) file.oss << ", ";
|
if (argumentList(i).size() > 0) file.oss << ", ";
|
||||||
argumentList(i).emit_cython_pyx(file);
|
argumentList(i).emit_cython_pyx(file);
|
||||||
|
@ -109,8 +115,8 @@ void Method::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
// ... casting return value
|
// ... casting return value
|
||||||
returnVals_[i].emit_cython_pyx_casting(file);
|
returnVals_[i].emit_cython_pyx_casting(file);
|
||||||
if (!returnVals_[i].isVoid()) file.oss << "(";
|
if (!returnVals_[i].isVoid()) file.oss << "(";
|
||||||
file.oss << "self." << cls.pyxCythonObj() << "." << funcName;
|
file.oss << "self." << cls.pyxCythonObj() << ".get()." << funcName;
|
||||||
// if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
||||||
|
|
||||||
// ... argument list
|
// ... argument list
|
||||||
file.oss << "(";
|
file.oss << "(";
|
||||||
|
|
|
@ -334,9 +334,11 @@ void Module::emit_cython_pxd(FileWriter& pxdFile) const {
|
||||||
void Module::emit_cython_pyx(FileWriter& pyxFile) const {
|
void Module::emit_cython_pyx(FileWriter& pyxFile) const {
|
||||||
// headers...
|
// headers...
|
||||||
pyxFile.oss << "cimport numpy as np\n"
|
pyxFile.oss << "cimport numpy as np\n"
|
||||||
"cimport gtsam_wrapper as gtsam\n"
|
"cimport cythontest_wrapper as gtsam\n"
|
||||||
"from gtsam_wrapper cimport shared_ptr\n"
|
"from cythontest_wrapper cimport shared_ptr\n"
|
||||||
"from eigency.core cimport *\n"
|
"from eigency.core cimport *\n"
|
||||||
|
"from libcpp cimport bool\n\n"
|
||||||
|
"from libcpp.pair cimport pair\n"
|
||||||
"from libcpp.string cimport string\n"
|
"from libcpp.string cimport string\n"
|
||||||
"from cython.operator cimport dereference as deref\n\n\n";
|
"from cython.operator cimport dereference as deref\n\n\n";
|
||||||
for(const Class& cls: expandedClasses)
|
for(const Class& cls: expandedClasses)
|
||||||
|
|
|
@ -185,16 +185,17 @@ public:
|
||||||
|
|
||||||
/// return the Cython class in pxd corresponding to a Python class in pyx
|
/// return the Cython class in pxd corresponding to a Python class in pyx
|
||||||
std::string pyxCythonClass() const {
|
std::string pyxCythonClass() const {
|
||||||
if (isNonBasicType())
|
if (isNonBasicType()) {
|
||||||
if (namespaces_.size() > 0)
|
if (namespaces_.size() > 0)
|
||||||
return namespaces_[0] + "." + cythonClassName();
|
return namespaces_[0] + "." + cythonClassName();
|
||||||
else {
|
else {
|
||||||
std::cerr << "Class without namespace: " << cythonClassName() << std::endl;
|
std::cerr << "Class without namespace: " << cythonClassName() << std::endl;
|
||||||
throw std::runtime_error("Error: User type without namespace!!");
|
throw std::runtime_error("Error: User type without namespace!!");
|
||||||
}
|
}
|
||||||
|
}
|
||||||
else if (isEigen()) {
|
else if (isEigen()) {
|
||||||
return name_ + "Xd";
|
return name_ + "Xd";
|
||||||
} else
|
} else // basic types and not Eigen
|
||||||
return name_;
|
return name_;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -67,13 +67,11 @@ void ReturnType::wrapTypeUnwrap(FileWriter& wrapperFile) const {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
void ReturnType::emit_cython_pxd(FileWriter& file) const {
|
void ReturnType::emit_cython_pxd(FileWriter& file) const {
|
||||||
string typeName = qualifiedName("_");
|
string typeName = cythonClassName();
|
||||||
string cythonType = typeName;
|
string cythonType;
|
||||||
if (typeName=="Vector" || typeName == "Matrix") {
|
if (isEigen()) cythonType = typeName + "Xd";
|
||||||
cythonType = typeName + "Xd";
|
else if (isPtr) cythonType = "shared_ptr[" + typeName + "]";
|
||||||
} else {
|
else cythonType = typeName;
|
||||||
if (isPtr) cythonType = "shared_ptr[" + typeName + "]";
|
|
||||||
}
|
|
||||||
file.oss << cythonType;
|
file.oss << cythonType;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -85,6 +83,8 @@ void ReturnType::emit_cython_pyx_casting(FileWriter& file) const {
|
||||||
if (isPtr)
|
if (isPtr)
|
||||||
file.oss << pythonClassName() << ".cyCreateFromShared";
|
file.oss << pythonClassName() << ".cyCreateFromShared";
|
||||||
else {
|
else {
|
||||||
|
// if the function return an object, it must be copy constructible and copy assignable
|
||||||
|
// so it's safe to use cyCreateFromValue
|
||||||
file.oss << pythonClassName() << ".cyCreateFromValue";
|
file.oss << pythonClassName() << ".cyCreateFromValue";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -86,11 +86,17 @@ void ReturnValue::emit_cython_pxd(FileWriter& file) const {
|
||||||
void ReturnValue::emit_cython_pyx_casting(FileWriter& file) const {
|
void ReturnValue::emit_cython_pyx_casting(FileWriter& file) const {
|
||||||
if (isVoid()) return;
|
if (isVoid()) return;
|
||||||
if (isPair) {
|
if (isPair) {
|
||||||
file.oss << "(";
|
// file.oss << "cdef pair[" << type1.pyxCythonClass() << "," << type2.pyxCythonClass() << "]"
|
||||||
type1.emit_cython_pyx_casting(file);
|
// << "ret = ";
|
||||||
file.oss << ",";
|
// file.oss << "(";
|
||||||
type2.emit_cython_pyx_casting(file);
|
// type1.emit_cython_pyx_casting(file);
|
||||||
file.oss << ")";
|
// file.oss << "(";
|
||||||
|
// file.oss << type1.pyxCythonClass();
|
||||||
|
// file.oss << "),";
|
||||||
|
// type2.emit_cython_pyx_casting(file);
|
||||||
|
// file.oss << "(";
|
||||||
|
// file.oss << type2.pyxCythonClass();
|
||||||
|
// file.oss << "))";
|
||||||
} else {
|
} else {
|
||||||
type1.emit_cython_pyx_casting(file);
|
type1.emit_cython_pyx_casting(file);
|
||||||
}
|
}
|
||||||
|
|
|
@ -63,7 +63,9 @@ void StaticMethod::emit_cython_pxd(FileWriter& file) const {
|
||||||
file.oss << "\t\t@staticmethod\n";
|
file.oss << "\t\t@staticmethod\n";
|
||||||
file.oss << "\t\t";
|
file.oss << "\t\t";
|
||||||
returnVals_[i].emit_cython_pxd(file);
|
returnVals_[i].emit_cython_pxd(file);
|
||||||
file.oss << name_ << ((i>0)?"_"+to_string(i):"") << "(";
|
file.oss << name_ << ((i > 0) ? "_" + to_string(i) : "") << " \"" << name_
|
||||||
|
<< "\""
|
||||||
|
<< "(";
|
||||||
argumentList(i).emit_cython_pxd(file);
|
argumentList(i).emit_cython_pxd(file);
|
||||||
file.oss << ")\n";
|
file.oss << ")\n";
|
||||||
}
|
}
|
||||||
|
@ -74,17 +76,23 @@ void StaticMethod::emit_cython_pyx(FileWriter& file, const Class& cls) const {
|
||||||
// don't support overloads for static method :-(
|
// don't support overloads for static method :-(
|
||||||
for(size_t i = 0; i < nrOverloads(); ++i) {
|
for(size_t i = 0; i < nrOverloads(); ++i) {
|
||||||
file.oss << "\t@staticmethod\n";
|
file.oss << "\t@staticmethod\n";
|
||||||
file.oss << "\tdef " << name_ << ((i>0)? "_" + to_string(i):"") << "(";
|
file.oss << "\tdef " << name_ << ((i > 0) ? "_" + to_string(i) : "")
|
||||||
|
<< "(";
|
||||||
argumentList(i).emit_cython_pyx(file);
|
argumentList(i).emit_cython_pyx(file);
|
||||||
file.oss << "):\n";
|
file.oss << "):\n";
|
||||||
file.oss << "\t\t";
|
file.oss << "\t\t";
|
||||||
if (!returnVals_[i].isVoid()) file.oss << "return ";
|
if (!returnVals_[i].isVoid()) file.oss << "return ";
|
||||||
file.oss << cls.pythonClassName() << ".cyCreate("
|
//... casting return value
|
||||||
<< cls.pyxCythonClass() << "."
|
returnVals_[i].emit_cython_pyx_casting(file);
|
||||||
<< name_ << ((i>0)? "_" + to_string(i):"")
|
if (!returnVals_[i].isVoid()) file.oss << "(";
|
||||||
<< "(";
|
|
||||||
|
file.oss << cls.pyxCythonClass() << "."
|
||||||
|
<< name_ << ((i>0)? "_" + to_string(i):"");
|
||||||
|
if (templateArgValue_) file.oss << "[" << templateArgValue_->pyxCythonClass() << "]";
|
||||||
|
file.oss << "(";
|
||||||
argumentList(i).emit_cython_pyx_asParams(file);
|
argumentList(i).emit_cython_pyx_asParams(file);
|
||||||
file.oss << "))\n";
|
if (!returnVals_[i].isVoid()) file.oss << ")";
|
||||||
|
file.oss << ")\n";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -15,10 +15,129 @@ typedef gtsam::FastSet<size_t> KeySet;
|
||||||
#include <gtsam/base/FastMap.h>
|
#include <gtsam/base/FastMap.h>
|
||||||
template<K,V> class FastMap{};
|
template<K,V> class FastMap{};
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Point2.h>
|
||||||
|
class Point2 {
|
||||||
|
// Standard Constructors
|
||||||
|
Point2();
|
||||||
|
Point2(double x, double y);
|
||||||
|
// Point2(Vector v);
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::Point2& pose, double tol) const;
|
||||||
|
|
||||||
|
// Group
|
||||||
|
static gtsam::Point2 identity();
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
|
double x() const;
|
||||||
|
double y() const;
|
||||||
|
Vector vector() const;
|
||||||
|
double distance(const gtsam::Point2& p2) const;
|
||||||
|
double norm() const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
};
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Rot2.h>
|
||||||
|
class Rot2 {
|
||||||
|
// Standard Constructors and Named Constructors
|
||||||
|
Rot2();
|
||||||
|
Rot2(double theta);
|
||||||
|
static gtsam::Rot2 fromAngle(double theta);
|
||||||
|
static gtsam::Rot2 fromDegrees(double theta);
|
||||||
|
static gtsam::Rot2 fromCosSin(double c, double s);
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::Rot2& rot, double tol) const;
|
||||||
|
|
||||||
|
// Group
|
||||||
|
static gtsam::Rot2 identity();
|
||||||
|
gtsam::Rot2 inverse();
|
||||||
|
gtsam::Rot2 compose(const gtsam::Rot2& p2) const;
|
||||||
|
gtsam::Rot2 between(const gtsam::Rot2& p2) const;
|
||||||
|
|
||||||
|
// Manifold
|
||||||
|
gtsam::Rot2 retract(Vector v) const;
|
||||||
|
Vector localCoordinates(const gtsam::Rot2& p) const;
|
||||||
|
|
||||||
|
// Lie Group
|
||||||
|
static gtsam::Rot2 Expmap(Vector v);
|
||||||
|
static Vector Logmap(const gtsam::Rot2& p);
|
||||||
|
|
||||||
|
// Group Action on Point2
|
||||||
|
gtsam::Point2 rotate(const gtsam::Point2& point) const;
|
||||||
|
gtsam::Point2 unrotate(const gtsam::Point2& point) const;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
|
static gtsam::Rot2 relativeBearing(const gtsam::Point2& d); // Ignoring derivative
|
||||||
|
static gtsam::Rot2 atan2(double y, double x);
|
||||||
|
double theta() const;
|
||||||
|
double degrees() const;
|
||||||
|
double c() const;
|
||||||
|
double s() const;
|
||||||
|
Matrix matrix() const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
};
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Pose2.h>
|
||||||
|
class Pose2 {
|
||||||
|
// Standard Constructor
|
||||||
|
Pose2();
|
||||||
|
Pose2(const gtsam::Pose2& pose);
|
||||||
|
Pose2(double x, double y, double theta);
|
||||||
|
Pose2(double theta, const gtsam::Point2& t);
|
||||||
|
Pose2(const gtsam::Rot2& r, const gtsam::Point2& t);
|
||||||
|
// Pose2(Vector v);
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::Pose2& pose, double tol) const;
|
||||||
|
|
||||||
|
// Group
|
||||||
|
static gtsam::Pose2 identity();
|
||||||
|
gtsam::Pose2 inverse() const;
|
||||||
|
gtsam::Pose2 compose(const gtsam::Pose2& p2) const;
|
||||||
|
gtsam::Pose2 between(const gtsam::Pose2& p2) const;
|
||||||
|
|
||||||
|
// Manifold
|
||||||
|
gtsam::Pose2 retract(Vector v) const;
|
||||||
|
Vector localCoordinates(const gtsam::Pose2& p) const;
|
||||||
|
|
||||||
|
// Lie Group
|
||||||
|
static gtsam::Pose2 Expmap(Vector v);
|
||||||
|
static Vector Logmap(const gtsam::Pose2& p);
|
||||||
|
Matrix AdjointMap() const;
|
||||||
|
Vector Adjoint(const Vector& xi) const;
|
||||||
|
static Matrix wedge(double vx, double vy, double w);
|
||||||
|
|
||||||
|
// Group Actions on Point2
|
||||||
|
gtsam::Point2 transform_from(const gtsam::Point2& p) const;
|
||||||
|
gtsam::Point2 transform_to(const gtsam::Point2& p) const;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
|
double x() const;
|
||||||
|
double y() const;
|
||||||
|
double theta() const;
|
||||||
|
gtsam::Rot2 bearing(const gtsam::Point2& point) const;
|
||||||
|
double range(const gtsam::Point2& point) const;
|
||||||
|
gtsam::Point2 translation() const;
|
||||||
|
gtsam::Rot2 rotation() const;
|
||||||
|
Matrix matrix() const;
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/geometry/Point3.h>
|
#include <gtsam/geometry/Point3.h>
|
||||||
class Point3 {
|
class Point3 {
|
||||||
// Standard Constructors
|
// Standard Constructors
|
||||||
Point3();
|
Point3();
|
||||||
|
Point3(const Point3& p);
|
||||||
Point3(double x, double y, double z);
|
Point3(double x, double y, double z);
|
||||||
Point3(Vector v);
|
Point3(Vector v);
|
||||||
|
|
||||||
|
@ -43,6 +162,7 @@ class Point3 {
|
||||||
class Rot3 {
|
class Rot3 {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
Rot3();
|
Rot3();
|
||||||
|
Rot3(const Rot3& R);
|
||||||
Rot3(Matrix R);
|
Rot3(Matrix R);
|
||||||
static gtsam::Rot3 Rx(double t);
|
static gtsam::Rot3 Rx(double t);
|
||||||
static gtsam::Rot3 Ry(double t);
|
static gtsam::Rot3 Ry(double t);
|
||||||
|
@ -94,6 +214,54 @@ class Rot3 {
|
||||||
void serialize() const;
|
void serialize() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/geometry/Pose3.h>
|
||||||
|
class Pose3 {
|
||||||
|
// Standard Constructors
|
||||||
|
Pose3();
|
||||||
|
Pose3(const gtsam::Pose3& pose);
|
||||||
|
Pose3(const gtsam::Rot3& r, const gtsam::Point3& t);
|
||||||
|
Pose3(const gtsam::Pose2& pose2); // FIXME: shadows Pose3(Pose3 pose)
|
||||||
|
Pose3(Matrix t);
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::Pose3& pose, double tol) const;
|
||||||
|
|
||||||
|
// Group
|
||||||
|
static gtsam::Pose3 identity();
|
||||||
|
gtsam::Pose3 inverse() const;
|
||||||
|
gtsam::Pose3 compose(const gtsam::Pose3& p2) const;
|
||||||
|
gtsam::Pose3 between(const gtsam::Pose3& p2) const;
|
||||||
|
|
||||||
|
// Manifold
|
||||||
|
gtsam::Pose3 retract(Vector v) const;
|
||||||
|
Vector localCoordinates(const gtsam::Pose3& T2) const;
|
||||||
|
|
||||||
|
// Lie Group
|
||||||
|
static gtsam::Pose3 Expmap(Vector v);
|
||||||
|
static Vector Logmap(const gtsam::Pose3& p);
|
||||||
|
Matrix AdjointMap() const;
|
||||||
|
Vector Adjoint(Vector xi) const;
|
||||||
|
static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz);
|
||||||
|
|
||||||
|
// Group Action on Point3
|
||||||
|
gtsam::Point3 transform_from(const gtsam::Point3& p) const;
|
||||||
|
gtsam::Point3 transform_to(const gtsam::Point3& p) const;
|
||||||
|
|
||||||
|
// Standard Interface
|
||||||
|
gtsam::Rot3 rotation() const;
|
||||||
|
gtsam::Point3 translation() const;
|
||||||
|
double x() const;
|
||||||
|
double y() const;
|
||||||
|
double z() const;
|
||||||
|
Matrix matrix() const;
|
||||||
|
gtsam::Pose3 transform_to(const gtsam::Pose3& pose) const; // FIXME: shadows other transform_to()
|
||||||
|
double range(const gtsam::Point3& point);
|
||||||
|
double range(const gtsam::Pose3& pose);
|
||||||
|
|
||||||
|
// enabling serialization functionality
|
||||||
|
void serialize() const;
|
||||||
|
};
|
||||||
|
|
||||||
#include <gtsam/linear/VectorValues.h>
|
#include <gtsam/linear/VectorValues.h>
|
||||||
class VectorValues {
|
class VectorValues {
|
||||||
|
@ -153,8 +321,6 @@ virtual class Diagonal : gtsam::noiseModel::Gaussian {
|
||||||
static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas);
|
static gtsam::noiseModel::Diagonal* Sigmas(Vector sigmas);
|
||||||
static gtsam::noiseModel::Diagonal* Variances(Vector variances);
|
static gtsam::noiseModel::Diagonal* Variances(Vector variances);
|
||||||
static gtsam::noiseModel::Diagonal* Precisions(Vector precisions);
|
static gtsam::noiseModel::Diagonal* Precisions(Vector precisions);
|
||||||
Matrix R() const;
|
|
||||||
void print(string s) const;
|
|
||||||
|
|
||||||
// enabling serialization functionality
|
// enabling serialization functionality
|
||||||
void serializable() const;
|
void serializable() const;
|
||||||
|
@ -213,7 +379,7 @@ virtual class GaussianFactor {
|
||||||
Matrix augmentedInformation() const;
|
Matrix augmentedInformation() const;
|
||||||
Matrix information() const;
|
Matrix information() const;
|
||||||
Matrix augmentedJacobian() const;
|
Matrix augmentedJacobian() const;
|
||||||
pair<Matrix, Vector> jacobian() const;
|
// pair<Matrix, Vector> jacobian() const;
|
||||||
size_t size() const;
|
size_t size() const;
|
||||||
bool empty() const;
|
bool empty() const;
|
||||||
};
|
};
|
||||||
|
@ -230,24 +396,20 @@ virtual class JacobianFactor : gtsam::GaussianFactor {
|
||||||
const gtsam::noiseModel::Diagonal* model);
|
const gtsam::noiseModel::Diagonal* model);
|
||||||
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3,
|
JacobianFactor(size_t i1, Matrix A1, size_t i2, Matrix A2, size_t i3, Matrix A3,
|
||||||
Vector b, const gtsam::noiseModel::Diagonal* model);
|
Vector b, const gtsam::noiseModel::Diagonal* model);
|
||||||
JacobianFactor(const gtsam::GaussianFactorGraph& graph);
|
// JacobianFactor(const gtsam::GaussianFactorGraph& graph);
|
||||||
|
|
||||||
//Testable
|
//Testable
|
||||||
void print(string s) const;
|
|
||||||
void printKeys(string s) const;
|
void printKeys(string s) const;
|
||||||
bool equals(const gtsam::GaussianFactor& lf, double tol) const;
|
|
||||||
size_t size() const;
|
|
||||||
Vector unweighted_error(const gtsam::VectorValues& c) const;
|
Vector unweighted_error(const gtsam::VectorValues& c) const;
|
||||||
Vector error_vector(const gtsam::VectorValues& c) const;
|
Vector error_vector(const gtsam::VectorValues& c) const;
|
||||||
double error(const gtsam::VectorValues& c) const;
|
|
||||||
|
|
||||||
//Standard Interface
|
//Standard Interface
|
||||||
Matrix getA() const;
|
Matrix py_getA() const;
|
||||||
Vector getb() const;
|
Vector py_getb() const;
|
||||||
size_t rows() const;
|
size_t rows() const;
|
||||||
size_t cols() const;
|
size_t cols() const;
|
||||||
bool isConstrained() const;
|
bool isConstrained() const;
|
||||||
pair<Matrix, Vector> jacobianUnweighted() const;
|
// pair<Matrix, Vector> jacobianUnweighted() const;
|
||||||
Matrix augmentedJacobianUnweighted() const;
|
Matrix augmentedJacobianUnweighted() const;
|
||||||
|
|
||||||
void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const;
|
void transposeMultiplyAdd(double alpha, const Vector& e, gtsam::VectorValues& x) const;
|
||||||
|
@ -298,10 +460,10 @@ class Values {
|
||||||
// void update(size_t j, const gtsam::Value& val);
|
// void update(size_t j, const gtsam::Value& val);
|
||||||
// gtsam::Value at(size_t j) const;
|
// gtsam::Value at(size_t j) const;
|
||||||
|
|
||||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
template<T = {gtsam::Point3, gtsam::Rot3}>
|
||||||
void insert(size_t j, const T& t);
|
void insert(size_t j, const T& t);
|
||||||
|
|
||||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
template<T = {gtsam::Point3, gtsam::Rot3}>
|
||||||
void update(size_t j, const T& t);
|
void update(size_t j, const T& t);
|
||||||
|
|
||||||
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
template<T = {gtsam::Point3, gtsam::Rot3, Vector, Matrix}>
|
||||||
|
|
Loading…
Reference in New Issue