OKVIS
|
The Map class. This keeps track of how parameter blocks are connected to residual blocks. In essence, it encapsulates the ceres::Problem. This way, we can easily manipulate the optimisation problem. You could argue why not use cere's internal mechanisms to do that. We found that our implementation was faster... More...
#include <Map.hpp>
Classes | |
struct | ResidualBlockSpec |
Struct to store some infos about a residual. More... | |
Public Types | |
enum | Parameterization { HomogeneousPoint, Pose6d, Pose3d, Pose4d, Pose2d, Trivial } |
The Parameterisation enum. More... | |
typedef std::pair< uint64_t, std::shared_ptr < okvis::ceres::ParameterBlock > > | ParameterBlockSpec |
typedef std::vector < ResidualBlockSpec > | ResidualBlockCollection |
typedef std::vector < ParameterBlockSpec > | ParameterBlockCollection |
typedef std::unordered_map < uint64_t, std::shared_ptr < okvis::ceres::ParameterBlock > > | Id2ParameterBlock_Map |
The actual map from Id to parameter block pointer. More... | |
typedef std::unordered_map < ::ceres::ResidualBlockId, ResidualBlockSpec > | ResidualBlockId2ResidualBlockSpec_Map |
The actual map from Id to residual block specs. More... | |
Public Member Functions | |
Map () | |
Constructor. More... | |
bool | parameterBlockExists (uint64_t parameterBlockId) const |
Check whether a certain parameter block is part of the map. More... | |
void | getLhs (uint64_t parameterBlockId, Eigen::MatrixXd &H) |
Obtain the Hessian block for a specific parameter block. More... | |
bool | isJacobianCorrect (::ceres::ResidualBlockId residualBlockId, double relTol=1e-6) const |
Check a Jacobian with numeric differences. More... | |
const Id2ParameterBlock_Map & | id2parameterBlockMap () const |
Get map connecting parameter block IDs to parameter blocks. More... | |
const ResidualBlockId2ResidualBlockSpec_Map & | residualBlockId2ResidualBlockSpecMap () const |
Get the actual map from Id to residual block specs. More... | |
void | solve () |
Solve the optimization problem. More... | |
Print info | |
void | printParameterBlockInfo (uint64_t parameterBlockId) const |
Log information on a parameter block. More... | |
void | printResidualBlockInfo (::ceres::ResidualBlockId residualBlockId) const |
Log information on a residual block. More... | |
add/remove | |
bool | addParameterBlock (std::shared_ptr< okvis::ceres::ParameterBlock > parameterBlock, int parameterization=Parameterization::Trivial, const int group=-1) |
Add a parameter block to the map. More... | |
bool | removeParameterBlock (uint64_t parameterBlockId) |
Remove a parameter block from the map. More... | |
bool | removeParameterBlock (std::shared_ptr< okvis::ceres::ParameterBlock > parameterBlock) |
Remove a parameter block from the map. More... | |
::ceres::ResidualBlockId | addResidualBlock (std::shared_ptr< ::ceres::CostFunction > cost_function,::ceres::LossFunction *loss_function, std::vector< std::shared_ptr< okvis::ceres::ParameterBlock > > ¶meterBlockPtrs) |
Adds a residual block. More... | |
void | resetResidualBlock (::ceres::ResidualBlockId residualBlockId, std::vector< std::shared_ptr< okvis::ceres::ParameterBlock > > ¶meterBlockPtrs) |
Replace the parameters connected to a residual block ID. More... | |
::ceres::ResidualBlockId | addResidualBlock (std::shared_ptr< ::ceres::CostFunction > cost_function,::ceres::LossFunction *loss_function, std::shared_ptr< okvis::ceres::ParameterBlock > x0, std::shared_ptr< okvis::ceres::ParameterBlock > x1=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x2=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x3=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x4=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x5=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x6=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x7=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x8=std::shared_ptr< okvis::ceres::ParameterBlock >(), std::shared_ptr< okvis::ceres::ParameterBlock > x9=std::shared_ptr< okvis::ceres::ParameterBlock >()) |
Add a residual block. See respective ceres docu. If more are needed, see other interface. More... | |
bool | removeResidualBlock (::ceres::ResidualBlockId id) |
Remove a residual block. More... | |
Set constant/variable/local parameterization | |
bool | setParameterBlockConstant (uint64_t parameterBlockId) |
Do not optimise a certain parameter block. More... | |
bool | setParameterBlockVariable (uint64_t parameterBlockId) |
Optimise a certain parameter block (this is the default). More... | |
bool | setParameterBlockConstant (std::shared_ptr< okvis::ceres::ParameterBlock > parameterBlock) |
Do not optimise a certain parameter block. More... | |
bool | setParameterBlockVariable (std::shared_ptr< okvis::ceres::ParameterBlock > parameterBlock) |
Optimise a certain parameter block (this is the default). More... | |
bool | resetParameterization (uint64_t parameterBlockId, int parameterization) |
Reset the (local) parameterisation of a parameter block. More... | |
bool | setParameterization (uint64_t parameterBlockId,::ceres::LocalParameterization *local_parameterization) |
Set the (local) parameterisation of a parameter block. More... | |
bool | setParameterization (std::shared_ptr< okvis::ceres::ParameterBlock > parameterBlock,::ceres::LocalParameterization *local_parameterization) |
Set the (local) parameterisation of a parameter block. More... | |
Getters | |
std::shared_ptr < okvis::ceres::ParameterBlock > | parameterBlockPtr (uint64_t parameterBlockId) |
Get a shared pointer to a parameter block. More... | |
std::shared_ptr< const okvis::ceres::ParameterBlock > | parameterBlockPtr (uint64_t parameterBlockId) const |
Get a shared pointer to a parameter block. More... | |
std::shared_ptr < okvis::ceres::ErrorInterface > | errorInterfacePtr (::ceres::ResidualBlockId residualBlockId) |
Get a shared pointer to an error term. More... | |
std::shared_ptr< const okvis::ceres::ErrorInterface > | errorInterfacePtr (::ceres::ResidualBlockId residualBlockId) const |
Get a shared pointer to an error term. More... | |
ResidualBlockCollection | residuals (uint64_t parameterBlockId) const |
Get the residual blocks of a parameter block. More... | |
ParameterBlockCollection | parameters (::ceres::ResidualBlockId residualBlockId) const |
Get the parameters of a residual block. More... | |
Public Attributes | |
::ceres::Solver::Options | options |
Ceres options. More... | |
::ceres::Solver::Summary | summary |
Ceres optimization summary. More... | |
Protected Types | |
typedef std::unordered_multimap < uint64_t, ResidualBlockSpec > | Id2ResidualBlock_Multimap |
Go from Id to residual block pointer. More... | |
typedef std::unordered_map < ::ceres::ResidualBlockId, ParameterBlockCollection > | ResidualBlockId2ParameterBlockCollection_Map |
Go from residual block id to its parameter blocks. More... | |
The Map class. This keeps track of how parameter blocks are connected to residual blocks. In essence, it encapsulates the ceres::Problem. This way, we can easily manipulate the optimisation problem. You could argue why not use cere's internal mechanisms to do that. We found that our implementation was faster...
typedef std::unordered_map<uint64_t, std::shared_ptr<okvis::ceres::ParameterBlock> > okvis::ceres::Map::Id2ParameterBlock_Map |
The actual map from Id to parameter block pointer.
|
protected |
Go from Id to residual block pointer.
typedef std::vector<ParameterBlockSpec> okvis::ceres::Map::ParameterBlockCollection |
typedef std::pair<uint64_t, std::shared_ptr<okvis::ceres::ParameterBlock> > okvis::ceres::Map::ParameterBlockSpec |
typedef std::vector<ResidualBlockSpec> okvis::ceres::Map::ResidualBlockCollection |
|
protected |
Go from residual block id to its parameter blocks.
typedef std::unordered_map< ::ceres::ResidualBlockId, ResidualBlockSpec> okvis::ceres::Map::ResidualBlockId2ResidualBlockSpec_Map |
The actual map from Id to residual block specs.
The Parameterisation enum.
Enumerator | |
---|---|
HomogeneousPoint | |
Pose6d | |
Pose3d |
Use okvis::ceres::PoseLocalParameterization3d (orientation varying). |
Pose4d |
Use okvis::ceres::PoseLocalParameterization4d (position and yaw varying). |
Pose2d |
Use okvis::ceres::PoseLocalParameterization2d (roll/pitch varying). |
Trivial |
No local parameterisation. |
okvis::ceres::Map::Map | ( | ) |
Constructor.
bool okvis::ceres::Map::addParameterBlock | ( | std::shared_ptr< okvis::ceres::ParameterBlock > | parameterBlock, |
int | parameterization = Parameterization::Trivial , |
||
const int | group = -1 |
||
) |
Add a parameter block to the map.
parameterBlock | Parameter block to insert. |
parameterization | okvis::ceres::Parameterization to tell how to do the local parameterisation. |
group | Schur elimination group – currently unused. |
ceres::ResidualBlockId okvis::ceres::Map::addResidualBlock | ( | std::shared_ptr< ::ceres::CostFunction > | cost_function, |
::ceres::LossFunction * | loss_function, | ||
std::vector< std::shared_ptr< okvis::ceres::ParameterBlock > > & | parameterBlockPtrs | ||
) |
Adds a residual block.
[in] | cost_function | The error term to be used. |
[in] | loss_function | Use an m-estimator? NULL, if not needed. |
[in] | parameterBlockPtrs | A vector that contains all the parameter blocks the error term relates to. |
ceres::ResidualBlockId okvis::ceres::Map::addResidualBlock | ( | std::shared_ptr< ::ceres::CostFunction > | cost_function, |
::ceres::LossFunction * | loss_function, | ||
std::shared_ptr< okvis::ceres::ParameterBlock > | x0, | ||
std::shared_ptr< okvis::ceres::ParameterBlock > | x1 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x2 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x3 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x4 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x5 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x6 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x7 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x8 = std::shared_ptr< okvis::ceres::ParameterBlock>() , |
||
std::shared_ptr< okvis::ceres::ParameterBlock > | x9 = std::shared_ptr< okvis::ceres::ParameterBlock>() |
||
) |
Add a residual block. See respective ceres docu. If more are needed, see other interface.
[in] | cost_function | The error term to be used. |
[in] | loss_function | Use an m-estimator? NULL, if not needed. |
[in] | x0 | The first parameter block. |
[in] | x1 | The second parameter block (if existent). |
[in] | x2 | The third parameter block (if existent). |
[in] | x3 | The 4th parameter block (if existent). |
[in] | x4 | The 5th parameter block (if existent). |
[in] | x5 | The 6th parameter block (if existent). |
[in] | x6 | The 7th parameter block (if existent). |
[in] | x7 | The 8th parameter block (if existent). |
[in] | x8 | The 9th parameter block (if existent). |
[in] | x9 | The 10th parameter block (if existent). |
std::shared_ptr< okvis::ceres::ErrorInterface > okvis::ceres::Map::errorInterfacePtr | ( | ::ceres::ResidualBlockId | residualBlockId | ) |
Get a shared pointer to an error term.
std::shared_ptr< const okvis::ceres::ErrorInterface > okvis::ceres::Map::errorInterfacePtr | ( | ::ceres::ResidualBlockId | residualBlockId | ) | const |
Get a shared pointer to an error term.
void okvis::ceres::Map::getLhs | ( | uint64_t | parameterBlockId, |
Eigen::MatrixXd & | H | ||
) |
Obtain the Hessian block for a specific parameter block.
[in] | parameterBlockId | Parameter block ID of interest. |
[out] | H | the output Hessian block. |
|
inline |
Get map connecting parameter block IDs to parameter blocks.
bool okvis::ceres::Map::isJacobianCorrect | ( | ::ceres::ResidualBlockId | residualBlockId, |
double | relTol = 1e-6 |
||
) | const |
Check a Jacobian with numeric differences.
[in] | residualBlockId | The ID of the residual block to be checked. |
[in] | relTol | Relative numeric tolerance. |
bool okvis::ceres::Map::parameterBlockExists | ( | uint64_t | parameterBlockId | ) | const |
Check whether a certain parameter block is part of the map.
parameterBlockId | ID of parameter block to find. |
std::shared_ptr< okvis::ceres::ParameterBlock > okvis::ceres::Map::parameterBlockPtr | ( | uint64_t | parameterBlockId | ) |
Get a shared pointer to a parameter block.
std::shared_ptr< const okvis::ceres::ParameterBlock > okvis::ceres::Map::parameterBlockPtr | ( | uint64_t | parameterBlockId | ) | const |
Get a shared pointer to a parameter block.
Map::ParameterBlockCollection okvis::ceres::Map::parameters | ( | ::ceres::ResidualBlockId | residualBlockId | ) | const |
Get the parameters of a residual block.
[in] | residualBlockId | The ID of the residual block in question. |
void okvis::ceres::Map::printParameterBlockInfo | ( | uint64_t | parameterBlockId | ) | const |
Log information on a parameter block.
void okvis::ceres::Map::printResidualBlockInfo | ( | ::ceres::ResidualBlockId | residualBlockId | ) | const |
Log information on a residual block.
bool okvis::ceres::Map::removeParameterBlock | ( | uint64_t | parameterBlockId | ) |
Remove a parameter block from the map.
parameterBlockId | ID of block to remove. |
bool okvis::ceres::Map::removeParameterBlock | ( | std::shared_ptr< okvis::ceres::ParameterBlock > | parameterBlock | ) |
Remove a parameter block from the map.
parameterBlock | Pointer to the block to remove. |
bool okvis::ceres::Map::removeResidualBlock | ( | ::ceres::ResidualBlockId | id | ) |
Remove a residual block.
[in] | id | The residual block ID of the residual block to be removed. |
bool okvis::ceres::Map::resetParameterization | ( | uint64_t | parameterBlockId, |
int | parameterization | ||
) |
Reset the (local) parameterisation of a parameter block.
[in] | parameterBlockId | The ID of the parameter block in question. |
[in] | parameterization | okvis::ceres::Parameterization to tell how to do the local parameterisation. |
void okvis::ceres::Map::resetResidualBlock | ( | ::ceres::ResidualBlockId | residualBlockId, |
std::vector< std::shared_ptr< okvis::ceres::ParameterBlock > > & | parameterBlockPtrs | ||
) |
Replace the parameters connected to a residual block ID.
[in] | residualBlockId | The ID of the residual block the parameter blocks of which are to be to be replaced. |
[in] | parameterBlockPtrs | A vector containing the parameter blocks to be replaced. |
|
inline |
Get the actual map from Id to residual block specs.
Map::ResidualBlockCollection okvis::ceres::Map::residuals | ( | uint64_t | parameterBlockId | ) | const |
Get the residual blocks of a parameter block.
[in] | parameterBlockId | The ID of the parameter block in question. |
bool okvis::ceres::Map::setParameterBlockConstant | ( | uint64_t | parameterBlockId | ) |
Do not optimise a certain parameter block.
[in] | parameterBlockId | The parameter block ID of the parameter block to set fixed. |
|
inline |
Do not optimise a certain parameter block.
[in] | parameterBlock | Pointer to the parameter block that should be constant. |
bool okvis::ceres::Map::setParameterBlockVariable | ( | uint64_t | parameterBlockId | ) |
Optimise a certain parameter block (this is the default).
[in] | parameterBlockId | The parameter block ID of the parameter block to set fixed. |
|
inline |
Optimise a certain parameter block (this is the default).
[in] | parameterBlock | Pointer to the parameter block that should be optimised. |
bool okvis::ceres::Map::setParameterization | ( | uint64_t | parameterBlockId, |
::ceres::LocalParameterization * | local_parameterization | ||
) |
Set the (local) parameterisation of a parameter block.
[in] | parameterBlockId | The ID of the parameter block in question. |
[in] | local_parameterization | Give it an actual local parameterisation object. |
|
inline |
Set the (local) parameterisation of a parameter block.
[in] | parameterBlock | The pointer to the parameter block in question. |
[in] | local_parameterization | Give it an actual local parameterisation object. |
|
inline |
Solve the optimization problem.
|
protected |
Store parameterisation locally.
|
protected |
The map connecting parameter block ID's and parameter blocks.
|
protected |
Go from Id to residual block pointer.
::ceres::Solver::Options okvis::ceres::Map::options |
Ceres options.
|
protected |
Store parameterisation locally.
|
protected |
Store parameterisation locally.
|
protected |
Store parameterisation locally.
|
protected |
Store parameterisation locally.
|
protected |
The ceres problem.
|
protected |
Go from residual block id to its parameter blocks.
|
protected |
Go from residual ID to specs.
|
protected |
count the inserted residual blocks.
::ceres::Solver::Summary okvis::ceres::Map::summary |
Ceres optimization summary.