Skip to content
Snippets Groups Projects
Commit 8f61af3e authored by Joan Solà Ortega's avatar Joan Solà Ortega
Browse files

Add namespace wolf to all files in /ceres_wrapper/

parent 4e70c195
No related branches found
No related tags found
No related merge requests found
Showing with 52 additions and 1 deletion
......@@ -8,7 +8,7 @@
#include "ceres/jet.h"
#include "ceres/sized_cost_function.h"
namespace wolf {
template <class ConstraintType, const unsigned int MEASUREMENT_SIZE,
unsigned int BLOCK_0_SIZE, unsigned int BLOCK_1_SIZE, unsigned int BLOCK_2_SIZE, unsigned int BLOCK_3_SIZE, unsigned int BLOCK_4_SIZE,
......@@ -1113,4 +1113,6 @@ class AutoDiffCostFunctionWrapperBase<ConstraintType, MEASUREMENT_SIZE,
}
};
} // namespace wolf
#endif /* TRUNK_SRC_AUTODIFF_COST_FUNCTION_WRAPPER_BASE_H_ */
#include "ceres_manager.h"
namespace wolf {
CeresManager::CeresManager(WolfProblem* _wolf_problem, ceres::Problem::Options _options) :
ceres_problem_(new ceres::Problem(_options)),
wolf_problem_(_wolf_problem)
......@@ -283,3 +285,6 @@ ceres::CostFunction* CeresManager::createCostFunction(ConstraintBase* _corrPtr,
else
throw std::invalid_argument( "Bad Jacobian Method!" );
}
} // namespace wolf
......@@ -14,6 +14,10 @@
#include "create_auto_diff_cost_function.h"
#include "create_numeric_diff_cost_function.h"
namespace wolf {
/** \brief Enumeration of covariance blocks to be computed
*
* Enumeration of covariance blocks to be computed
......@@ -65,4 +69,6 @@ class CeresManager
ceres::CostFunction* createCostFunction(ConstraintBase* _corrPtr, const bool _self_auto_diff);
};
} // namespace wolf
#endif
......@@ -8,6 +8,8 @@
// CERES
#include "ceres/cost_function.h"
namespace wolf {
class CostFunctionWrapper : public ceres::CostFunction
{
protected:
......@@ -65,4 +67,8 @@ class CostFunctionWrapper : public ceres::CostFunction
}
};
} // namespace wolf
#endif /* TRUNK_SRC_COST_FUNCTION_WRAPPER_H_ */
......@@ -22,6 +22,8 @@
#include "create_auto_diff_cost_function_wrapper.h"
#include "create_auto_diff_cost_function_ceres.h"
namespace wolf {
ceres::CostFunction* createAutoDiffCostFunction(ConstraintBase* _ctr_ptr, bool _use_wolf_autodiff)
{
switch (_ctr_ptr->getType())
......@@ -81,4 +83,6 @@ ceres::CostFunction* createAutoDiffCostFunction(ConstraintBase* _ctr_ptr, bool _
}
}
} // namespace wolf
#endif /* SRC_CERES_WRAPPER_CREATE_AUTO_DIFF_COST_FUNCTION_H_ */
......@@ -10,6 +10,8 @@
#include "ceres/autodiff_cost_function.h"
namespace wolf {
template <class CtrType>
ceres::AutoDiffCostFunction<CtrType,
CtrType::measurementSize,
......@@ -37,5 +39,6 @@ ceres::AutoDiffCostFunction<CtrType,
CtrType::block5Size,CtrType::block6Size,CtrType::block7Size,CtrType::block8Size,CtrType::block9Size>((CtrType*)_constraint_ptr);
};
} // namespace wolf
#endif /* SRC_CERES_WRAPPER_CREATE_AUTO_DIFF_COST_FUNCTION_CERES_H_ */
......@@ -10,6 +10,8 @@
#include "auto_diff_cost_function_wrapper.h"
namespace wolf {
template <class CtrType>
AutoDiffCostFunctionWrapperBase<CtrType,
CtrType::measurementSize,
......@@ -37,4 +39,6 @@ AutoDiffCostFunctionWrapperBase<CtrType,
CtrType::block5Size,CtrType::block6Size,CtrType::block7Size,CtrType::block8Size,CtrType::block9Size>((CtrType*)_constraint_ptr);
};
} // namespace wolf
#endif /* SRC_CERES_WRAPPER_CREATE_AUTO_DIFF_COST_FUNCTION_WRAPPER_H_ */
......@@ -14,6 +14,8 @@
// Wolf and ceres auto_diff creators
#include "create_numeric_diff_cost_function_ceres.h"
namespace wolf {
ceres::CostFunction* createNumericDiffCostFunction(ConstraintBase* _ctr_ptr, bool _use_wolf_numericdiff)
{
if (_use_wolf_numericdiff)
......@@ -35,4 +37,6 @@ ceres::CostFunction* createNumericDiffCostFunction(ConstraintBase* _ctr_ptr, boo
}
}
} // namespace wolf
#endif /* SRC_CERES_WRAPPER_CREATE_NUMERIC_DIFF_COST_FUNCTION_H_ */
......@@ -10,6 +10,8 @@
#include "ceres/numeric_diff_cost_function.h"
namespace wolf {
template <class CtrType>
ceres::NumericDiffCostFunction<CtrType, ceres::CENTRAL,
CtrType::measurementSize,
......@@ -40,4 +42,6 @@ ceres::NumericDiffCostFunction<CtrType, ceres::CENTRAL,
} // namespace wolf
#endif /* SRC_CERES_WRAPPER_CREATE_NUMERIC_DIFF_COST_FUNCTION_CERES_H_ */
#include "local_parametrization_wrapper.h"
namespace wolf {
bool LocalParametrizationWrapper::Plus(const double* x_raw, const double* delta_raw, double* x_plus_delta_raw) const
{
Eigen::Map<const Eigen::VectorXs> x_raw_map(x_raw, GlobalSize());
......@@ -14,3 +16,6 @@ bool LocalParametrizationWrapper::ComputeJacobian(const double* x, double* jacob
Eigen::Map<Eigen::MatrixXs> jacobian_map(jacobian, GlobalSize(), LocalSize());
return local_parametrization_ptr_->computeJacobian(x_map, jacobian_map);
};
} // namespace wolf
......@@ -9,6 +9,8 @@ class LocalParametrizationBase;
//Ceres includes
#include "ceres/ceres.h"
namespace wolf {
class LocalParametrizationWrapper : public ceres::LocalParameterization
{
private:
......@@ -29,8 +31,12 @@ class LocalParametrizationWrapper : public ceres::LocalParameterization
virtual int LocalSize() const;
};
} // namespace wolf
#include "local_parametrization_base.h"
namespace wolf {
inline LocalParametrizationWrapper::LocalParametrizationWrapper(LocalParametrizationBase* _local_parametrization_ptr) :
local_parametrization_ptr_(_local_parametrization_ptr)
{
......@@ -50,4 +56,6 @@ inline int LocalParametrizationWrapper::LocalSize() const
return local_parametrization_ptr_->getLocalSize();
}
} // namespace wolf
#endif
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment