roboptim Namespace Reference

defined(EIGEN_RUNTIME_NO_MALLOC) && !defined(ROBOPTIM_DO_NOT_CHECK_ALLOCATION) More...

Namespaces

namespace  callback
namespace  detail
namespace  fg
namespace  finiteDifferenceGradientPolicies
 

Contains finite difference gradients policies.


namespace  visualization
 

Graphical visualization.


Classes

class  LRUCache
 LRU (Least Recently Used) cache. More...
struct  Hasher
 Hash generator for argument vector. More...
class  CachedFunction
 Store previous function computation. More...
class  BadGradient
 Exception thrown when a gradient check fails. More...
class  BadJacobian
 Exception thrown when a Jacobian check fails. More...
class  GenericFiniteDifferenceGradient
 Compute automatically a gradient with finite differences. More...
class  DerivableParametrizedFunction
 Parametrized function with parameter derivative available. More...
struct  derivativeSize< GenericFunction< T > >
struct  derivativeSize< GenericDifferentiableFunction< T > >
struct  derivativeSize< GenericTwiceDifferentiableFunction< T > >
struct  derivativeSize< NTimesDerivableFunction< N > >
class  GenericDifferentiableFunction
 Define an abstract derivable function ( \(C^1\)). More...
class  GenericConstantFunction
 Constant function. More...
class  Cos
 Cos function. More...
class  GenericIdentityFunction
 Identity function. More...
class  Polynomial
 Polynomial function. More...
class  Sin
 Sin function. More...
class  FunctionPool
 A pool of functions that will be processed together. More...
struct  GenericFunctionTraits
 GenericFunction traits. More...
class  GenericFunction
 Define an abstract mathematical function ( \(C^0\)). More...
struct  GenericFunctionTraits< EigenMatrixDense >
 Trait specializing GenericFunction for Eigen dense matrices. More...
struct  GenericFunctionTraits< EigenMatrixSparse >
 Trait specializing GenericFunction for Eigen sparse matrices. More...
class  NoSolution
 Tag a result if no solution has been found. More...
struct  EigenMatrixDense
 Tag type for functions using Eigen dense matrices. More...
struct  EigenMatrixSparse
 Tag type for functions using Eigen sparse matrices. More...
class  GenericSolver
 Abstract interface satisfied by all solvers. More...
class  GenericLinearFunction
 Define an abstract linear function. More...
class  NTimesDerivableFunction< 2 >
 Explicit specialization for the stop case of NTimesDerivable class. More...
class  NTimesDerivableFunction
 Define a \(\mathbb{R} \rightarrow \mathbb{R}^m\) function, derivable n times ( \(n \geq 2\)). More...
class  GenericNumericLinearFunction
 Build a linear function from a vector and a matrix. More...
class  GenericNumericQuadraticFunction
 Build a quadratic function from a matrix and a vector. More...
class  Bind
 Bind some function input to a constant value. More...
class  Chain
 Chain two RobOptim functions. More...
class  Concatenate
 Concatenate the output of two functions. More...
class  Derivative
 Return the derivative of a function w.r.t. More...
class  Map
 Apply a function several times to an input vector. More...
class  Minus
 Subtract two RobOptim functions. More...
class  Plus
 Sum two RobOptim functions. More...
class  Product
 Product of two RobOptim functions. More...
class  Scalar
 Multiply by a constant scalar value. More...
class  SelectionById
 Select part of a function. More...
class  Selection
 Select a block of a function's output. More...
class  Split
 Select an element of a function's output. More...
class  OptimizationLogger
 Log the optimization process (values, Jacobians, time taken etc.). More...
class  ParametrizedFunction
 Define an abstract parametrized mathematical function ( \(C^0\)). More...
class  GenericDummySolverLastState
 Dummy solver which always fails, but returns the last state of the solver. More...
class  DummySolverTd
 Dummy solver which always fails. More...
class  DummySolver
 Dummy solver which always fails. More...
class  Problem
class  GenericQuadraticFunction
 Define an abstract quadratic function. More...
class  ResultWithWarnings
 Represents the solution of an optimization problem when errors occurred during the solving process. More...
class  Result
 Represents the solution of an optimization problem. More...
class  SolverCallback
 Solver per-iteration callback wrapper. More...
class  SolverError
 Base exception class for solving errors. More...
class  SolverFactory
 Define a solver factory that instanciate the plug-ins. More...
struct  StateParameter
 Solver state parameters type. More...
class  SolverState
 State of the solver. More...
class  SolverWarning
 Exception used for non-critical errors during optimization. More...
struct  Parameter
 Solver parameter type. More...
class  Solver
 Solver for a specific problem class. More...
class  GenericSumOfC1Squares
 Generic sum of the squares of differentiable functions. More...
class  GenericTwiceDifferentiableFunction
 Define an abstract function which is twice-derivable ( \(C^2\)). More...

Typedefs

typedef DifferentiableFunction DerivableFunction
 Legacy name of TwiceDifferentiableFunction.
typedef
DifferentiableSparseFunction 
DerivableSparseFunction
 Legacy name of TwiceDifferentiableSparseFunction.
typedef GenericFunction
< EigenMatrixDense
Function
 Dense function.
typedef GenericFunction
< EigenMatrixSparse
SparseFunction
 Sparse function.
typedef
GenericDifferentiableFunction
< EigenMatrixDense
DifferentiableFunction
 Dense differentiable function.
typedef
GenericDifferentiableFunction
< EigenMatrixSparse
DifferentiableSparseFunction
 Sparse differentiable function.
typedef
GenericNumericLinearFunction
< EigenMatrixDense
NumericLinearFunction
typedef
GenericNumericLinearFunction
< EigenMatrixSparse
NumericLinearSparseFunction
typedef
GenericNumericQuadraticFunction
< EigenMatrixDense
NumericQuadraticFunction
typedef
GenericNumericQuadraticFunction
< EigenMatrixSparse
NumericQuadraticSparseFunction
typedef
GenericConstantFunction
< EigenMatrixDense
ConstantFunction
typedef
GenericIdentityFunction
< EigenMatrixDense
IdentityFunction
typedef
GenericTwiceDifferentiableFunction
< EigenMatrixDense
TwiceDifferentiableFunction
typedef
GenericTwiceDifferentiableFunction
< EigenMatrixSparse
TwiceDifferentiableSparseFunction
typedef GenericLinearFunction
< EigenMatrixDense
LinearFunction
typedef GenericLinearFunction
< EigenMatrixSparse
LinearSparseFunction
typedef
GenericQuadraticFunction
< EigenMatrixDense
QuadraticFunction
typedef
GenericQuadraticFunction
< EigenMatrixSparse
QuadraticSparseFunction
typedef
GenericDummySolverLastState
< EigenMatrixDense
DummySolverLastState
typedef
GenericDummySolverLastState
< EigenMatrixSparse
DummyDifferentiableSparseSolverLastState
typedef GenericSumOfC1Squares
< EigenMatrixDense
SumOfC1Squares
 Sum of the squares of dense differentiable functions.
typedef GenericSumOfC1Squares
< EigenMatrixSparse
SumOfC1SquaresSparse
 Sum of the squares of sparse differentiable functions.
typedef TwiceDifferentiableFunction TwiceDerivableFunction
 Legacy name of DifferentiableFunction.

Enumerations

enum  FunctionFlag {
  ROBOPTIM_IS_FUNCTION = 1 << 0,
  ROBOPTIM_IS_DIFFERENTIABLE = 1 << 1,
  ROBOPTIM_IS_TWICE_DIFFERENTIABLE = 1 << 2,
  ROBOPTIM_IS_QUADRATIC = 1 << 3,
  ROBOPTIM_IS_NUMERIC_QUADRATIC = 1 << 4,
  ROBOPTIM_IS_LINEAR = 1 << 5,
  ROBOPTIM_IS_NUMERIC_LINEAR = 1 << 6,
  ROBOPTIM_IS_POLYNOMIAL = 1 << 7,
  ROBOPTIM_IS_CONSTANT = 1 << 8
}
 Bit flags describing the type of function. More...

Functions

ROBOPTIM_DLLAPI bool is_malloc_allowed_update (bool update=false, bool new_value=false)
 Update the static variable used for Eigen::set_is_malloc_allowed.
bool set_is_malloc_allowed (bool allow)
 Manage the calls to Eigen::set_is_malloc_allowed.
bool is_malloc_allowed ()
 Whether dynamic allocation is allowed.
template<typename K , typename V , typename H >
std::ostream & operator<< (std::ostream &o, const LRUCache< K, V, H > &cache)
template<typename T >
std::ostream & operator<< (std::ostream &o, const BadGradient< T > &f)
 Override operator<< to handle exception display.
template<typename T >
std::ostream & operator<< (std::ostream &o, const BadJacobian< T > &f)
 Override operator<< to handle exception display.
template<typename T >
bool checkGradient (const GenericDifferentiableFunction< T > &function, typename GenericDifferentiableFunction< T >::size_type functionId, typename GenericDifferentiableFunction< T >::const_argument_ref x, typename GenericDifferentiableFunction< T >::value_type threshold=finiteDifferenceThreshold)
 Check if a gradient is valid.
template<typename T >
void checkGradientAndThrow (const GenericDifferentiableFunction< T > &function, typename GenericDifferentiableFunction< T >::size_type functionId, typename GenericDifferentiableFunction< T >::const_argument_ref x, typename GenericDifferentiableFunction< T >::value_type threshold=finiteDifferenceThreshold) throw (BadGradient<T>)
template<typename T >
bool checkJacobian (const GenericDifferentiableFunction< T > &function, typename GenericDifferentiableFunction< T >::const_argument_ref x, typename GenericDifferentiableFunction< T >::value_type threshold=finiteDifferenceThreshold)
 Check if a Jacobian is valid.
template<typename T >
void checkJacobianAndThrow (const GenericDifferentiableFunction< T > &function, typename GenericDifferentiableFunction< T >::const_argument_ref x, typename GenericDifferentiableFunction< T >::value_type threshold=finiteDifferenceThreshold) throw (BadJacobian<T>)
template<typename T >
std::ostream & operator<< (std::ostream &o, const GenericFunction< T > &f)
 Override operator<< to handle function display.
template<typename U , typename V >
boost::shared_ptr< V > castInto (boost::shared_ptr< U > &u)
 Cast a shared_ptr of function to a different function type.
template<typename U , typename V >
const boost::shared_ptr< V > castInto (const boost::shared_ptr< U > &u)
 Cast a shared_ptr of function to a different function type.
template<typename T >
std::string typeString ()
 Return a string describing the type of T.
ROBOPTIM_DLLAPI std::ostream & operator<< (std::ostream &o, const GenericSolver &gs)
 Override operator<< to handle solver display.
ROBOPTIM_DLLAPI std::ostream & operator<< (std::ostream &o, const NoSolution &ns)
 Override operator<< to display ``no solution'' objects.
ROBOPTIM_DLLAPI long int & indent (std::ostream &o)
 The current indentation level for o.
ROBOPTIM_DLLAPI std::ostream & incindent (std::ostream &o)
 Increment the indentation.
ROBOPTIM_DLLAPI std::ostream & decindent (std::ostream &o)
 Decrement the indentation.
ROBOPTIM_DLLAPI std::ostream & resetindent (std::ostream &o)
 Reset the indentation.
ROBOPTIM_DLLAPI std::ostream & iendl (std::ostream &o)
 Print an end of line, then set the indentation.
ROBOPTIM_DLLAPI std::ostream & incendl (std::ostream &o)
 Increment the indentation, print an end of line, and set the indentation.
ROBOPTIM_DLLAPI std::ostream & decendl (std::ostream &o)
 Decrement the indentation, print an end of line, and set the indentation.
template<typename U >
boost::shared_ptr< Bind< U > > bind (boost::shared_ptr< U > origin, const typename Bind< U >::boundValues_t &boundValues)
template<typename U , typename V >
boost::shared_ptr< Chain< U, V > > chain (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
 Chain two RobOptim functions.
template<typename U , typename V >
boost::shared_ptr< Concatenate
< typename
detail::PromoteTrait< U, V >
::T_promote > > 
concatenate (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U >
boost::shared_ptr< Derivative
< U > > 
derivative (boost::shared_ptr< U > origin, typename Derivative< U >::size_type variableId=0)
template<typename U >
boost::shared_ptr< Map< U > > map (boost::shared_ptr< U > origin, typename U::size_type repeat)
template<typename U , typename V >
boost::shared_ptr< Minus< U, V > > minus (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U , typename V >
boost::shared_ptr< Minus< U, V > > operator- (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U , typename V >
boost::shared_ptr< Plus< U, V > > plus (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U , typename V >
boost::shared_ptr< Plus< U, V > > operator+ (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U , typename V >
boost::shared_ptr< Product< U,
V > > 
product (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U , typename V >
boost::shared_ptr< Product< U,
V > > 
operator* (boost::shared_ptr< U > left, boost::shared_ptr< V > right)
template<typename U >
boost::shared_ptr< Scalar< U > > scalar (boost::shared_ptr< U > origin, typename Scalar< U >::size_type start=0, typename Scalar< U >::size_type size=1)
template<typename U >
boost::shared_ptr< Scalar< U > > operator* (typename Scalar< U >::value_type scalar, boost::shared_ptr< U > origin)
template<typename U >
boost::shared_ptr< Scalar< U > > operator* (boost::shared_ptr< U > origin, typename Scalar< U >::value_type scalar)
template<typename U >
boost::shared_ptr< U > operator+ (boost::shared_ptr< U > origin)
template<typename U >
boost::shared_ptr< Scalar< U > > operator- (boost::shared_ptr< U > origin)
template<typename U >
boost::shared_ptr
< SelectionById< U > > 
selectionById (boost::shared_ptr< U > origin, std::vector< bool > selector)
template<typename U >
boost::shared_ptr< Selection< U > > selection (boost::shared_ptr< U > origin, typename Selection< U >::size_type start=0, typename Selection< U >::size_type size=1)
template<typename P , typename C >
void addNonScalarConstraint (P &problem, boost::shared_ptr< C > constraint, std::vector< Function::interval_t > interval, std::vector< Function::value_type > scale=std::vector< Function::value_type >())
template<typename F >
std::ostream & operator<< (std::ostream &o, const ParametrizedFunction< F > &f)
 Override operator<< to handle function display.
template<typename T >
std::ostream & operator<< (std::ostream &o, const Problem< T > &pb)
 Override operator<< to handle problem display.
ROBOPTIM_DLLAPI std::ostream & operator<< (std::ostream &o, const Result &r)
 Override operator<< to handle result display.
template<typename S >
std::ostream & operator<< (std::ostream &o, const SolverCallback< S > &c)
ROBOPTIM_DLLAPI std::ostream & operator<< (std::ostream &o, const SolverError &e)
 Override operator<< to handle error display.
template<typename S >
S * unionCast (void *ptr)
template<typename F >
std::ostream & operator<< (std::ostream &o, const StateParameter< F > &parameter)
 Override operator<< to display ``parameters'' objects.
template<typename P >
std::ostream & operator<< (std::ostream &o, const SolverState< P > &state)
 Override operator<< to display ``parameters'' objects.
ROBOPTIM_DLLAPI std::ostream & operator<< (std::ostream &o, const Parameter &parameter)
 Override operator<< to display ``parameters'' objects.
template<typename T >
std::ostream & operator<< (std::ostream &, const std::vector< T > &)
 Display a vector.
template<typename T1 , typename T2 >
std::ostream & operator<< (std::ostream &, const std::pair< T1, T2 > &)
 Display a pair.
template<typename T1 , typename T2 >
std::ostream & operator<< (std::ostream &, const std::map< T1, T2 > &)
 Display a map.
template<typename T >
std::ostream & operator<< (std::ostream &, const Eigen::MatrixBase< T > &)
 Display an Eigen object with the appropriate IOFormat.
ROBOPTIM_DLLAPI const std::string demangle (const char *name)
 Demangle (if available).
ROBOPTIM_DLLAPI
GenericFunctionTraits
< EigenMatrixDense >::matrix_t 
sparse_to_dense (GenericFunctionTraits< EigenMatrixSparse >::const_matrix_ref m)
 Convert a sparse matrix into a dense matrix.
ROBOPTIM_DLLAPI
GenericFunctionTraits
< EigenMatrixDense >::vector_t 
sparse_to_dense (GenericFunctionTraits< EigenMatrixSparse >::const_gradient_ref v)
 Convert a sparse vector into a dense vector.
ROBOPTIM_DLLAPI
GenericFunctionTraits
< EigenMatrixDense >
::gradient_t 
toDense (GenericFunctionTraits< EigenMatrixSparse >::const_gradient_ref g)
 Convert an input gradient to a dense gradient (e.g.
ROBOPTIM_DLLAPI
GenericFunctionTraits
< EigenMatrixDense >::matrix_t 
toDense (GenericFunctionTraits< EigenMatrixSparse >::const_matrix_ref m)
 Convert an input matrix to a dense matrix (e.g.
ROBOPTIM_DLLAPI
GenericFunctionTraits
< EigenMatrixDense >
::const_matrix_ref 
toDense (GenericFunctionTraits< EigenMatrixDense >::const_matrix_ref m)
 Convert an input matrix to a dense matrix (e.g.
ROBOPTIM_DLLAPI bool allclose (const Eigen::SparseMatrix< double > &a, const Eigen::SparseMatrix< double > &b, double rtol=Eigen::NumTraits< double >::dummy_precision(), double atol=Eigen::NumTraits< double >::epsilon())
 Compare sparse vectors (matrices) using both relative and absolute tolerances.
ROBOPTIM_DLLAPI bool allclose (const Eigen::Ref< const Eigen::MatrixXd > &a, const Eigen::Ref< const Eigen::MatrixXd > &b, double rtol=Eigen::NumTraits< double >::dummy_precision(), double atol=Eigen::NumTraits< double >::epsilon())
 Compare dense vectors (matrices) using both relative and absolute tolerances.
template<typename U >
void copySparseBlock (U &m, const U &b, Function::size_type startRow, Function::size_type startCol, bool compress=false)
 Copy a sparse block into a sparse matrix.
template<typename M , typename B >
void updateSparseBlock (M &m, const B &b, Function::size_type startRow, Function::size_type startCol)
 Update a sparse block of a sparse matrix.
double normalize (double x, double eps=1e-8)
 Apply normalize to a scalar.
template<typename T >
normalize (const T &x, double eps=1e-8)
 Apply normalize to each element of an Eigen vector.
GenericFunctionTraits
< EigenMatrixDense >
::const_gradient_ref 
toDense (GenericFunctionTraits< EigenMatrixDense >::const_gradient_ref m)

Variables

static const double finiteDifferenceThreshold = 1e-4
 Default threshold for checkGradient.
static const double finiteDifferenceEpsilon = 1e-8
 Default epsilon for finite difference class.
static const int StorageOrder = Eigen::ROBOPTIM_STORAGE_ORDER
 Default matrix storage order.
ROBOPTIM_ALLOW_ATTRIBUTES_ON
template class ROBOPTIM_DLLAPI 
GenericFunction< EigenMatrixDense >
template class ROBOPTIM_DLLAPI GenericFunction< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI GenericNumericQuadraticFunction< EigenMatrixDense >
template class ROBOPTIM_DLLAPI GenericNumericQuadraticFunction< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI GenericNumericLinearFunction< EigenMatrixDense >
template class ROBOPTIM_DLLAPI GenericNumericLinearFunction< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI GenericSumOfC1Squares< EigenMatrixDense >
template class ROBOPTIM_DLLAPI GenericSumOfC1Squares< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI Problem< EigenMatrixDense >
template class ROBOPTIM_DLLAPI Problem< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI Solver< EigenMatrixDense >
template class ROBOPTIM_DLLAPI Solver< EigenMatrixSparse >
template class ROBOPTIM_DLLAPI SolverFactory< Solver< EigenMatrixDense > >
template class ROBOPTIM_DLLAPI SolverFactory< Solver< EigenMatrixSparse > >
template class ROBOPTIM_DLLAPI SolverState< Problem< EigenMatrixDense > >
template class ROBOPTIM_DLLAPI SolverState< Problem< EigenMatrixSparse > >
template class ROBOPTIM_DLLAPI SolverCallback< Solver< EigenMatrixDense > >
template class ROBOPTIM_DLLAPI SolverCallback< Solver< EigenMatrixSparse > >
template class ROBOPTIM_DLLAPI OptimizationLogger< Solver< EigenMatrixDense > >
template class ROBOPTIM_DLLAPI OptimizationLogger< Solver< EigenMatrixSparse > >

Detailed Description

defined(EIGEN_RUNTIME_NO_MALLOC) && !defined(ROBOPTIM_DO_NOT_CHECK_ALLOCATION)

Meta-functions, functions and solver-related classes.

ROBOPTIM_CHECK_ALLOCATION


Typedef Documentation

Legacy name of TwiceDifferentiableFunction.

Legacy name of TwiceDifferentiableSparseFunction.

Legacy name of DifferentiableFunction.


Function Documentation

bool roboptim::allclose ( const Eigen::SparseMatrix< double > &  a,
const Eigen::SparseMatrix< double > &  b,
double  rtol = Eigen::NumTraits<double>::dummy_precision (),
double  atol = Eigen::NumTraits<double>::epsilon () 
)

Compare sparse vectors (matrices) using both relative and absolute tolerances.

See also:
http://stackoverflow.com/a/15052131/1043187
Examples:
numeric-linear-function.cc, and numeric-quadratic-function.cc.

Referenced by checkGradient(), and checkJacobian().

bool roboptim::allclose ( const Eigen::Ref< const Eigen::MatrixXd > &  a,
const Eigen::Ref< const Eigen::MatrixXd > &  b,
double  rtol = Eigen::NumTraits<double>::dummy_precision (),
double  atol = Eigen::NumTraits<double>::epsilon () 
)

Compare dense vectors (matrices) using both relative and absolute tolerances.

See also:
http://stackoverflow.com/a/15052131/1043187
template<typename U , typename V >
boost::shared_ptr< V > roboptim::castInto ( boost::shared_ptr< U > &  u)

Cast a shared_ptr of function to a different function type.

This throws if the cast is not possible.

Template Parameters:
Utype of the origin function.
Vnew function type.
Parameters:
uinput shared_ptr to a function.
Returns:
shared_ptr cast to the appropriate type.
template<typename U , typename V >
const boost::shared_ptr< V > roboptim::castInto ( const boost::shared_ptr< U > &  u)

Cast a shared_ptr of function to a different function type.

This throws if the cast is not possible. Const version.

Template Parameters:
Utype of the origin function.
Vnew function type.
Parameters:
uinput shared_ptr to a function.
Returns:
shared_ptr cast to the appropriate type.
template<typename U >
void roboptim::copySparseBlock ( U &  m,
const U &  b,
Function::size_type  startRow,
Function::size_type  startCol,
bool  compress = false 
)

Copy a sparse block into a sparse matrix.

This function involves filling a vector of triplets, so this should be avoided in critical sections.

Parameters:
mmatrix to fill.
bblock to copy to m.
startRowstart row of the block in m where b will be copied.
startColstart col of the block in m where b will be copied.
compresswhether to compress the sparse matrix at the end.
std::ostream & roboptim::decendl ( std::ostream &  o)

Decrement the indentation, print an end of line, and set the indentation.

References decindent(), and iendl().

const std::string roboptim::demangle ( const char *  name)

Demangle (if available).

Referenced by roboptim::SolverFactory< S >::SolverFactory(), and typeString().

std::ostream & roboptim::incendl ( std::ostream &  o)

Increment the indentation, print an end of line, and set the indentation.

References iendl(), and incindent().

Referenced by roboptim::Problem< T >::print().

bool roboptim::is_malloc_allowed_update ( bool  update = false,
bool  new_value = false 
)

Update the static variable used for Eigen::set_is_malloc_allowed.

Referenced by is_malloc_allowed(), and set_is_malloc_allowed().

template<typename T >
T roboptim::normalize ( const T &  x,
double  eps = 1e-8 
) [inline]

Apply normalize to each element of an Eigen vector.

template<typename T >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const std::vector< T > &  vect 
)

Display a vector.

template<typename T1 , typename T2 >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const std::pair< T1, T2 > &  p 
)

Display a pair.

template<typename T1 , typename T2 >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const std::map< T1, T2 > &  m 
)

Display a map.

template<typename T >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const Eigen::MatrixBase< T > &  matrix 
)

Display an Eigen object with the appropriate IOFormat.

std::ostream & roboptim::operator<< ( std::ostream &  o,
const SolverError &  e 
)

Override operator<< to handle error display.

Parameters:
ooutput stream used for display
eerror to be displayed
Returns:
output stream

References roboptim::SolverError::print().

std::ostream & roboptim::operator<< ( std::ostream &  o,
const Result &  r 
)

Override operator<< to handle result display.

Parameters:
ooutput stream used for display
rresult to be displayed
Returns:
output stream

References roboptim::Result::print().

template<typename S >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const SolverCallback< S > &  c 
)
template<typename F >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const ParametrizedFunction< F > &  f 
)

Override operator<< to handle function display.

Parameters:
ooutput stream used for display
ffunction to be displayed
Returns:
output stream
std::ostream & roboptim::operator<< ( std::ostream &  o,
const GenericSolver &  gs 
)

Override operator<< to handle solver display.

Parameters:
ooutput stream used for display
gssolver to be displayed
Returns:
output stream

References roboptim::GenericSolver::print().

std::ostream & roboptim::operator<< ( std::ostream &  o,
const NoSolution &  ns 
)

Override operator<< to display ``no solution'' objects.

Parameters:
ooutput stream used for display
nsNoSolution object, ignored
Returns:
output stream
template<typename K , typename V , typename H >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const LRUCache< K, V, H > &  cache 
)
template<typename T >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const Problem< T > &  pb 
)

Override operator<< to handle problem display.

Parameters:
ooutput stream used for display
pbproblem to be displayed
Returns:
output stream
template<typename T >
std::ostream & roboptim::operator<< ( std::ostream &  o,
const GenericFunction< T > &  f 
)

Override operator<< to handle function display.

Parameters:
ooutput stream used for display
ffunction to be displayed
Returns:
output stream
std::ostream & roboptim::resetindent ( std::ostream &  o)

Reset the indentation.

References indent().

GenericFunctionTraits< EigenMatrixDense >::matrix_t roboptim::sparse_to_dense ( GenericFunctionTraits< EigenMatrixSparse >::const_matrix_ref  m)

Convert a sparse matrix into a dense matrix.

GenericFunctionTraits< EigenMatrixDense >::vector_t roboptim::sparse_to_dense ( GenericFunctionTraits< EigenMatrixSparse >::const_gradient_ref  v)

Convert a sparse vector into a dense vector.

GenericFunctionTraits< EigenMatrixDense >::gradient_t roboptim::toDense ( GenericFunctionTraits< EigenMatrixSparse >::const_gradient_ref  g)

Convert an input gradient to a dense gradient (e.g.

for printing).

Parameters:
ginput gradient.
Examples:
numeric-linear-function.cc, and numeric-quadratic-function.cc.

Referenced by roboptim::GenericNumericLinearFunction< T >::print(), and roboptim::GenericNumericQuadraticFunction< T >::print().

GenericFunctionTraits< EigenMatrixDense >::matrix_t roboptim::toDense ( GenericFunctionTraits< EigenMatrixSparse >::const_matrix_ref  m)

Convert an input matrix to a dense matrix (e.g.

for printing).

Parameters:
minput matrix.
GenericFunctionTraits< EigenMatrixDense >::const_matrix_ref roboptim::toDense ( GenericFunctionTraits< EigenMatrixDense >::const_matrix_ref  m)

Convert an input matrix to a dense matrix (e.g.

for printing).

Parameters:
minput matrix. Note: since the input is a dense matrix, we just return it.
GenericFunctionTraits<EigenMatrixDense>::const_gradient_ref roboptim::toDense ( GenericFunctionTraits< EigenMatrixDense >::const_gradient_ref  m)
template<typename T >
std::string roboptim::typeString ( )

Return a string describing the type of T.

References demangle().

template<typename S >
S* roboptim::unionCast ( void *  ptr)
template<typename M , typename B >
void roboptim::updateSparseBlock ( M &  m,
const B &  b,
Function::size_type  startRow,
Function::size_type  startCol 
)

Update a sparse block of a sparse matrix.

This function expects the sparse matrix to have its structure set already, thus it can easily iterate over the values and copy them without any extra allocation. If that's not the case, the behavior is undefined.

Parameters:
msparse matrix to update.
bsparse block to copy to m.
startRowstart row of the block in m where b will be copied.
startColstart col of the block in m where b will be copied.
Template Parameters:
Mmatrix type.
Bblock type.

References BOOST_STATIC_ASSERT_MSG(), and ROBOPTIM_UNUSED.


Variable Documentation

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines