8 #ifndef SWITCHVARIABLESIGMOID_H_ 9 #define SWITCHVARIABLESIGMOID_H_ 13 #include <gtsam/base/DerivedValue.h> 14 #include <gtsam/base/Lie.h> 28 if (
d_ < -10.0)
d_=-10.0;
29 else if(
d_>10.0)
d_=10.0;
36 inline void print(
const std::string& name=
"")
const {
37 std::cout << name <<
": " <<
d_ << std::endl;
42 return fabs(expected.
d_ -
d_) <= tol;
48 inline size_t dim()
const {
return 1; }
49 inline static size_t Dim() {
return 1; }
53 double x =
value() + v(0);
56 else if (x<-10.0) x=-10.0;
78 boost::optional<gtsam::Matrix&> H1=boost::none,
79 boost::optional<gtsam::Matrix&> H2=boost::none)
const {
80 if(H1) *H1 = -gtsam::eye(1);
81 if(H2) *H2 = gtsam::eye(1);
106 template<
typename T>
struct traits;
112 return key1.
equals(key2, tol);
119 ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
123 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
static SwitchVariableSigmoid Expmap(const gtsam::Vector &v)
static gtsam::Vector Logmap(const SwitchVariableSigmoid &p)
void print(const std::string &name="") const
GLM_FUNC_DECL genType e()
static int GetDimension(const vertigo::SwitchVariableSigmoid &key)
static void Print(const vertigo::SwitchVariableSigmoid &key, const std::string &str="")
SwitchVariableSigmoid retract(const gtsam::Vector &v) const
static TangentVector Local(const vertigo::SwitchVariableSigmoid &origin, const vertigo::SwitchVariableSigmoid &other, ChartJacobian Horigin=boost::none, ChartJacobian Hother=boost::none)
gtsam::Vector localCoordinates(const SwitchVariableSigmoid &t2) const
OptionalJacobian< 3, 3 > ChartJacobian
static bool Equals(const vertigo::SwitchVariableSigmoid &key1, const vertigo::SwitchVariableSigmoid &key2, double tol=1e-8)
gtsam::Vector TangentVector
SwitchVariableSigmoid compose(const SwitchVariableSigmoid &p) const
static SwitchVariableSigmoid identity()
SwitchVariableSigmoid inverse() const
static vertigo::SwitchVariableSigmoid Retract(const vertigo::SwitchVariableSigmoid &g, const TangentVector &v, ChartJacobian H1=boost::none, ChartJacobian H2=boost::none)
bool equals(const SwitchVariableSigmoid &expected, double tol=1e-5) const
SwitchVariableSigmoid between(const SwitchVariableSigmoid &l2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const
SwitchVariableSigmoid(double d)