Class to do optimization.
More...
#include <optimizer.h>
Class to do optimization.
Definition at line 42 of file optimizer.h.
◆ Optimizer()
robot_calibration::Optimizer::Optimizer |
( |
const std::string & |
robot_description | ) |
|
◆ ~Optimizer()
robot_calibration::Optimizer::~Optimizer |
( |
| ) |
|
|
virtual |
◆ getCameraNames()
std::vector< std::string > robot_calibration::Optimizer::getCameraNames |
( |
| ) |
|
Get the names of all camera models.
This is mainly used when deciding what camera_info to export.
Definition at line 399 of file optimizer.cpp.
◆ getNumParameters()
int robot_calibration::Optimizer::getNumParameters |
( |
| ) |
|
|
inline |
◆ getNumResiduals()
int robot_calibration::Optimizer::getNumResiduals |
( |
| ) |
|
|
inline |
◆ getOffsets()
◆ optimize()
int robot_calibration::Optimizer::optimize |
( |
OptimizationParams & |
params, |
|
|
std::vector< robot_calibration_msgs::CalibrationData > |
data, |
|
|
bool |
progress_to_stdout = false |
|
) |
| |
Run optimization.
- Parameters
-
data | The data to be used for the optimization. Typically parsed from bag file, or loaded over some topic subscriber. |
progress_to_stdout | If true, Ceres optimizer will output info to stdout. |
Definition at line 63 of file optimizer.cpp.
◆ summary()
Returns the summary of the optimization last run.
Definition at line 63 of file optimizer.h.
◆ led_frame_
std::string robot_calibration::Optimizer::led_frame_ |
|
private |
◆ mesh_loader_
◆ model_
◆ models_
std::map<std::string, ChainModel*> robot_calibration::Optimizer::models_ |
|
private |
◆ num_params_
int robot_calibration::Optimizer::num_params_ |
|
private |
◆ num_residuals_
int robot_calibration::Optimizer::num_residuals_ |
|
private |
◆ offsets_
◆ root_frame_
std::string robot_calibration::Optimizer::root_frame_ |
|
private |
◆ summary_
◆ tree_
KDL::Tree robot_calibration::Optimizer::tree_ |
|
private |
The documentation for this class was generated from the following files: