Public Member Functions | Private Attributes
robot_calibration::Optimizer Class Reference

Class to do optimization. More...

#include <optimizer.h>

List of all members.

Public Member Functions

boost::shared_ptr
< CalibrationOffsetParser
getOffsets ()
int optimize (OptimizationParams &params, std::vector< robot_calibration_msgs::CalibrationData > data, bool progress_to_stdout=false)
 Run optimization.
 Optimizer (const std::string &robot_description)
 Standard constructor.
boost::shared_ptr
< ceres::Solver::Summary > 
summary ()
 Returns the summary of the optimization last run.
virtual ~Optimizer ()

Private Attributes

std::string led_frame_
urdf::Model model_
std::map< std::string,
ChainModel * > 
models_
boost::shared_ptr
< CalibrationOffsetParser
offsets_
std::string root_frame_
boost::shared_ptr
< ceres::Solver::Summary > 
summary_
KDL::Tree tree_

Detailed Description

Class to do optimization.

Definition at line 45 of file optimizer.h.


Constructor & Destructor Documentation

robot_calibration::Optimizer::Optimizer ( const std::string &  robot_description)

Standard constructor.

Definition at line 42 of file optimizer.cpp.

Definition at line 48 of file optimizer.cpp.


Member Function Documentation

Definition at line 69 of file optimizer.h.

int robot_calibration::Optimizer::optimize ( OptimizationParams params,
std::vector< robot_calibration_msgs::CalibrationData >  data,
bool  progress_to_stdout = false 
)

Run optimization.

Parameters:
dataThe data to be used for the optimization. Typically parsed from bag file, or loaded over some topic subscriber.
progress_to_stdoutIf true, Ceres optimizer will output info to stdout.

Definition at line 66 of file optimizer.cpp.

boost::shared_ptr<ceres::Solver::Summary> robot_calibration::Optimizer::summary ( ) [inline]

Returns the summary of the optimization last run.

Definition at line 64 of file optimizer.h.


Member Data Documentation

Definition at line 77 of file optimizer.h.

Definition at line 75 of file optimizer.h.

std::map<std::string, ChainModel*> robot_calibration::Optimizer::models_ [private]

Definition at line 80 of file optimizer.h.

Definition at line 82 of file optimizer.h.

Definition at line 76 of file optimizer.h.

boost::shared_ptr<ceres::Solver::Summary> robot_calibration::Optimizer::summary_ [private]

Definition at line 83 of file optimizer.h.

Definition at line 78 of file optimizer.h.


The documentation for this class was generated from the following files:


robot_calibration
Author(s): Michael Ferguson
autogenerated on Sat May 20 2017 02:35:31