Drake
|
NOTE: The contents of this class are for the most part direct ports of drake/systems/plants//inverseKinBackend.m from Matlab to C++; many methods and variables follow Matlab conventions and are documented in that file. More...
Namespaces | |
internal | |
RigidBodyConstraints | |
system_test | |
systems | |
Typedefs | |
template<typename ScalarType > | |
using | VecIn = Eigen::Ref< Eigen::Matrix< ScalarType, Eigen::Dynamic, 1 > const > |
template<typename ScalarType > | |
using | VecOut = Eigen::Matrix< ScalarType, Eigen::Dynamic, 1 > |
template<int num_vars> | |
using | TaylorVard = Eigen::AutoDiffScalar< Eigen::Matrix< double, num_vars, 1 > > |
template<int num_vars, int rows> | |
using | TaylorVecd = Eigen::Matrix< TaylorVard< num_vars >, rows, 1 > |
template<int num_vars, int rows, int cols> | |
using | TaylorMatd = Eigen::Matrix< TaylorVard< num_vars >, rows, cols > |
typedef TaylorVard< Eigen::Dynamic > | TaylorVarXd |
typedef TaylorVecd< Eigen::Dynamic, Eigen::Dynamic > | TaylorVecXd |
typedef TaylorMatd< Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic > | TaylorMatXd |
template<typename Derived , int Nq> | |
using | AutoDiffMatrixType = Eigen::Matrix< Eigen::AutoDiffScalar< Eigen::Matrix< typename Derived::Scalar, Nq, 1 > >, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime, 0, Derived::MaxRowsAtCompileTime, Derived::MaxColsAtCompileTime > |
The appropriate AutoDiffScalar gradient type given the value type and the number of derivatives at compile time. More... | |
typedef Eigen::Matrix< double, 1, 1 > | Vector1d |
template<typename ScalarType > | |
using | NullVector = Eigen::Matrix< ScalarType, 0, 1 > |
NullVector<ScalarType> More... | |
typedef std::chrono::system_clock | TimeClock |
typedef std::chrono::duration< double > | TimeDuration |
typedef std::chrono::time_point< TimeClock, TimeDuration > | TimePoint |
Functions | |
template<typename Derived , typename DerivedGradient , typename DerivedAutoDiff > | |
void | initializeAutoDiffGivenGradientMatrix (const Eigen::MatrixBase< Derived > &val, const Eigen::MatrixBase< DerivedGradient > &gradient, Eigen::MatrixBase< DerivedAutoDiff > &auto_diff_matrix) |
Initializes an autodiff matrix given a matrix of values and gradient matrix. More... | |
template<typename Derived , typename DerivedGradient > | |
AutoDiffMatrixType< Derived, DerivedGradient::ColsAtCompileTime > | initializeAutoDiffGivenGradientMatrix (const Eigen::MatrixBase< Derived > &val, const Eigen::MatrixBase< DerivedGradient > &gradient) |
Creates and initializes an autodiff matrix given a matrix of values and gradient matrix. More... | |
template<typename Derived , typename DerivedAutoDiff > | |
void | initializeAutoDiff (const Eigen::MatrixBase< Derived > &val, Eigen::MatrixBase< DerivedAutoDiff > &auto_diff_matrix, Eigen::DenseIndex num_derivatives=Eigen::Dynamic, Eigen::DenseIndex deriv_num_start=0) |
Initialize a single autodiff matrix given the corresponding value matrix. More... | |
template<int Nq = Eigen::Dynamic, typename Derived > | |
AutoDiffMatrixType< Derived, Nq > | initializeAutoDiff (const Eigen::MatrixBase< Derived > &mat, Eigen::DenseIndex num_derivatives=-1, Eigen::DenseIndex deriv_num_start=0) |
Initialize a single autodiff matrix given the corresponding value matrix. More... | |
template<typename... Args> | |
constexpr int | totalSizeAtCompileTime () |
Determine the total size at compile time of a number of arguments based on their SizeAtCompileTime static members. More... | |
constexpr Eigen::DenseIndex | totalSizeAtRunTime () |
Determine the total size at runtime of a number of arguments using their size() methods (base case). More... | |
template<typename Head , typename... Tail> | |
Eigen::DenseIndex | totalSizeAtRunTime (const Eigen::MatrixBase< Head > &head, const Tail &...tail) |
Determine the total size at runtime of a number of arguments using their size() methods (recursive) More... | |
template<typename... Deriveds> | |
std::tuple< AutoDiffMatrixType< Deriveds, totalSizeAtCompileTime< Deriveds... >)>... > | initializeAutoDiffTuple (const Eigen::MatrixBase< Deriveds > &...args) |
Given a series of Eigen matrices, create a tuple of corresponding AutoDiff matrices with values equal to the input matrices and properly initialized derivative vectors. More... | |
template<typename ScalarType , int Rows> | |
const Eigen::Matrix< ScalarType, Rows, 1 > & | toEigen (const Eigen::Matrix< ScalarType, Rows, 1 > &vec) |
template<template< typename > class VecType> | |
VecType< double > | getRandomVector (void) |
getRandomVector() More... | |
template<typename VecType > | |
std::size_t | size (const VecType &vec) |
size() More... | |
template<typename Vector > | |
std::string | getCoordinateName (const Vector &vec, unsigned int index) |
getCoordinateName() More... | |
template<typename System1 , typename System2 > | |
std::shared_ptr< CascadeSystem< System1, System2 > > | cascade (const std::shared_ptr< System1 > &sys1, const std::shared_ptr< System2 > &sys2) |
cascade(sys1, sys2) More... | |
template<typename System > | |
std::shared_ptr< AffineSystem< NullVector, System::template StateVector, System::template InputVector > > | timeInvariantLQR (const System &sys, const typename System::template StateVector< double > &x0, const typename System::template InputVector< double > &u0, const Eigen::MatrixXd &Q, const Eigen::MatrixXd &R) |
template<typename System1 , typename System2 > | |
std::shared_ptr< FeedbackSystem< System1, System2 > > | feedback (const std::shared_ptr< System1 > &sys1, const std::shared_ptr< System2 > &sys2) |
feedback(sys1, sys2) More... | |
template<class Vector > | |
bool | encode (const double &t, const Vector &x, drake::lcmt_drake_signal &msg) |
template<class Vector > | |
bool | decode (const drake::lcmt_drake_signal &msg, double &t, Vector &x) |
template<typename System > | |
void | runLCM (std::shared_ptr< System > sys, std::shared_ptr< lcm::LCM > lcm, double t0, double tf, const typename System::template StateVector< double > &x0, const SimulationOptions &options=default_simulation_options) |
runLCM More... | |
template<typename System > | |
void | runLCM (const System &sys, std::shared_ptr< lcm::LCM > lcm, double t0, double tf) |
DRAKERBSYSTEM_EXPORT RigidBodySystem::StateVector< double > | getInitialState (const RigidBodySystem &sys) |
void | parseForceElement (RigidBodySystem &sys, XMLElement *node) |
void | parseRobot (RigidBodySystem &sys, XMLElement *node) |
void | parseURDF (RigidBodySystem &sys, XMLDocument *xml_doc) |
void | parseSDFJoint (RigidBodySystem &sys, int model_id, XMLElement *node, PoseMap &pose_map) |
void | parseSDFLink (RigidBodySystem &sys, int model_id, XMLElement *node, PoseMap &pose_map) |
void | parseSDFModel (RigidBodySystem &sys, int model_id, XMLElement *node) |
void | parseSDF (RigidBodySystem &sys, XMLDocument *xml_doc) |
Eigen::VectorXd | spatialForceInFrameToJointTorque (const RigidBodyTree *tree, const KinematicsCache< double > &rigid_body_state, const RigidBodyFrame *frame, const Eigen::Matrix< double, 6, 1 > &force) |
spatialForceInFrameToJointTorque More... | |
bool | handle_realtime_factor (const TimePoint &wall_clock_start_time, double sim_time, double realtime_factor, double timeout_seconds) |
template<typename System > | |
double | simulate (const System &sys, double ti, double tf, const typename System::template StateVector< double > &xi, const SimulationOptions &options) |
simulate More... | |
template<typename System > | |
void | simulate (const System &sys, double t0, double tf, const typename System::template StateVector< double > &x0) |
simulate More... | |
template<typename System > | |
void | simulate (const System &sys, double t0, double tf) |
simulate More... | |
template<typename System > | |
std::size_t | getNumStates (const System &sys) |
getNumStates() More... | |
template<typename System > | |
std::size_t | getNumInputs (const System &sys) |
getNumInputs() More... | |
template<typename System > | |
std::size_t | getNumOutputs (const System &sys) |
getNumOutputs() More... | |
template<typename System > | |
System::template StateVector< double > | getInitialState (const System &sys) |
getInitialState() More... | |
template<typename Scalar , typename System > | |
System::template StateVector< Scalar > | createStateVector (const System &sys) |
Create a new, uninitialized state vector for the system. More... | |
template<typename Derived > | |
void | resizeDerivativesToMatchScalar (Eigen::MatrixBase< Derived > &mat, const typename Derived::Scalar &scalar) |
Resize derivatives vector of each element of a matrix to to match the size of the derivatives vector of a given scalar. More... | |
template<typename... Args, typename ReturnType > | |
auto | make_function (ReturnType(*p)(Args...)) -> std::function< ReturnType(Args...)> |
make_function Note that a completely general make_function implementation is not possible due to ambiguities, but this works for all of the cases in this file Inspired by http://stackoverflow.com/a/21740143/2228557 More... | |
template<typename... Args, typename ReturnType , typename ClassType > | |
auto | make_function (ReturnType(ClassType::*p)(Args...)) -> std::function< ReturnType(ClassType &, Args...)> |
Variables | |
static const SimulationOptions | default_simulation_options |
NOTE: The contents of this class are for the most part direct ports of drake/systems/plants//inverseKinBackend.m from Matlab to C++; many methods and variables follow Matlab conventions and are documented in that file.
using AutoDiffMatrixType = Eigen::Matrix< Eigen::AutoDiffScalar<Eigen::Matrix<typename Derived::Scalar, Nq, 1> >, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime, 0, Derived::MaxRowsAtCompileTime, Derived::MaxColsAtCompileTime> |
The appropriate AutoDiffScalar gradient type given the value type and the number of derivatives at compile time.
using TaylorMatd = Eigen::Matrix<TaylorVard<num_vars>, rows, cols> |
typedef TaylorMatd<Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic> TaylorMatXd |
using TaylorVard = Eigen::AutoDiffScalar<Eigen::Matrix<double, num_vars, 1> > |
typedef TaylorVard<Eigen::Dynamic> TaylorVarXd |
using TaylorVecd = Eigen::Matrix<TaylorVard<num_vars>, rows, 1> |
typedef TaylorVecd<Eigen::Dynamic, Eigen::Dynamic> TaylorVecXd |
typedef std::chrono::system_clock TimeClock |
typedef std::chrono::duration<double> TimeDuration |
typedef std::chrono::time_point<TimeClock, TimeDuration> TimePoint |
using VecIn = Eigen::Ref<Eigen::Matrix<ScalarType, Eigen::Dynamic, 1> const> |
using VecOut = Eigen::Matrix<ScalarType, Eigen::Dynamic, 1> |
bool Drake::decode | ( | const drake::lcmt_drake_signal & | msg, |
double & | t, | ||
Vector & | x | ||
) |
bool Drake::encode | ( | const double & | t, |
const Vector & | x, | ||
drake::lcmt_drake_signal & | msg | ||
) |
System::template StateVector<double> Drake::getInitialState | ( | const System & | sys | ) |
Returns a random feasible initial condition
DRAKERBSYSTEM_EXPORT RigidBodySystem::StateVector<double> Drake::getInitialState | ( | const RigidBodySystem & | sys | ) |
|
inline |
Determines whether the simulation time has lagged behind the real time beyond the specified
timeout_seconds
, after accounting for the real-time factor. If it has, throw a
std::runtime_error
exception.
wall_clock_start_time | The the simulation's start time. |
sim_time | The current simulation time. |
realtime_factor | The simulation's desired real-time factor. This is the speed at which the simulation should run relative to real-time. For example, 0 means the simulation should run as fast as possible, 1.0 means the simulation should run at real-time, and 2.0 means the simulation should run at 2X real-time speed. |
timeout_seconds | The maximum difference between the current time and the desired time (as determined based on the current simulation time and real-time factor) before which an exception is thrown. return True if the realtime factor was successfully handled. False otherwise. |
void Drake::initializeAutoDiff | ( | const Eigen::MatrixBase< Derived > & | val, |
Eigen::MatrixBase< DerivedAutoDiff > & | auto_diff_matrix, | ||
Eigen::DenseIndex | num_derivatives = Eigen::Dynamic , |
||
Eigen::DenseIndex | deriv_num_start = 0 |
||
) |
Initialize a single autodiff matrix given the corresponding value matrix.
Set the values of auto_diff_matrix
to be equal to val
, and for each element i of auto_diff_matrix
, resize the derivatives vector to num_derivatives
, and set derivative number deriv_num_start
+ i to one (all other elements of the derivative vector set to zero).
[in] | mat | 'regular' matrix of values |
[out] | ret | AutoDiff matrix |
[in] | num_derivatives | the size of the derivatives vector Default: the size of mat |
[in] | deriv_num_start | starting index into derivative vector (i.e. element deriv_num_start in derivative vector corresponds to mat(0, 0)). Default: 0 |
AutoDiffMatrixType<Derived, Nq> Drake::initializeAutoDiff | ( | const Eigen::MatrixBase< Derived > & | mat, |
Eigen::DenseIndex | num_derivatives = -1 , |
||
Eigen::DenseIndex | deriv_num_start = 0 |
||
) |
Initialize a single autodiff matrix given the corresponding value matrix.
Create autodiff matrix that matches mat
in size with derivatives of compile time size Nq
and runtime size num_derivatives
. Set its values to be equal to val
, and for each element i of auto_diff_matrix
, set derivative number deriv_num_start
+ i to one (all other derivatives set to zero).
[in] | mat | 'regular' matrix of values |
[in] | num_derivatives | the size of the derivatives vector Default: the size of mat |
[in] | deriv_num_start | starting index into derivative vector (i.e. element deriv_num_start in derivative vector corresponds to mat(0, 0)). Default: 0 |
void Drake::initializeAutoDiffGivenGradientMatrix | ( | const Eigen::MatrixBase< Derived > & | val, |
const Eigen::MatrixBase< DerivedGradient > & | gradient, | ||
Eigen::MatrixBase< DerivedAutoDiff > & | auto_diff_matrix | ||
) |
Initializes an autodiff matrix given a matrix of values and gradient matrix.
[in] | val | value matrix |
[in] | gradient | gradient matrix; the derivatives of val(j) are stored in row j of the gradient matrix. |
[out] | autodiff_matrix | matrix of AutoDiffScalars with the same size as val |
AutoDiffMatrixType<Derived, DerivedGradient::ColsAtCompileTime> Drake::initializeAutoDiffGivenGradientMatrix | ( | const Eigen::MatrixBase< Derived > & | val, |
const Eigen::MatrixBase< DerivedGradient > & | gradient | ||
) |
Creates and initializes an autodiff matrix given a matrix of values and gradient matrix.
[in] | val | value matrix |
[in] | gradient | gradient matrix; the derivatives of val(j) are stored in row j of the gradient matrix. |
val
std::tuple< AutoDiffMatrixType<Deriveds, totalSizeAtCompileTime<Deriveds...>)>...> Drake::initializeAutoDiffTuple | ( | const Eigen::MatrixBase< Deriveds > &... | args | ) |
Given a series of Eigen matrices, create a tuple of corresponding AutoDiff matrices with values equal to the input matrices and properly initialized derivative vectors.
The size of the derivative vector of each element of the matrices in the output tuple will be the same, and will equal the sum of the number of elements of the matrices in args
. If all of the matrices in args
have fixed size, then the derivative vectors will also have fixed size (being the sum of the sizes at compile time of all of the input arguments), otherwise the derivative vectors will have dynamic size. The 0th element of the derivative vectors will correspond to the derivative with respect to the 0th element of the first argument. Subsequent derivative vector elements correspond first to subsequent elements of the first input argument (traversed first by row, then by column), and so on for subsequent arguments.
args | a series of Eigen matrices |
args
auto Drake::make_function | ( | ReturnType(*)(Args...) | p | ) | -> std::function<ReturnType(Args...)> |
make_function Note that a completely general make_function implementation is not possible due to ambiguities, but this works for all of the cases in this file Inspired by http://stackoverflow.com/a/21740143/2228557
auto make_function | ( | ReturnType(ClassType::*)(Args...) | p | ) | -> std::function<ReturnType(ClassType&, Args...)> |
void Drake::parseForceElement | ( | RigidBodySystem & | sys, |
XMLElement * | node | ||
) |
void Drake::parseRobot | ( | RigidBodySystem & | sys, |
XMLElement * | node | ||
) |
void Drake::parseSDF | ( | RigidBodySystem & | sys, |
XMLDocument * | xml_doc | ||
) |
void Drake::parseSDFJoint | ( | RigidBodySystem & | sys, |
int | model_id, | ||
XMLElement * | node, | ||
PoseMap & | pose_map | ||
) |
void Drake::parseSDFLink | ( | RigidBodySystem & | sys, |
int | model_id, | ||
XMLElement * | node, | ||
PoseMap & | pose_map | ||
) |
void Drake::parseSDFModel | ( | RigidBodySystem & | sys, |
int | model_id, | ||
XMLElement * | node | ||
) |
void Drake::parseURDF | ( | RigidBodySystem & | sys, |
XMLDocument * | xml_doc | ||
) |
void Drake::resizeDerivativesToMatchScalar | ( | Eigen::MatrixBase< Derived > & | mat, |
const typename Derived::Scalar & | scalar | ||
) |
Resize derivatives vector of each element of a matrix to to match the size of the derivatives vector of a given scalar.
If the mat and scalar inputs are AutoDiffScalars, resize the derivatives vector of each element of the matrix mat to match the number of derivatives of the scalar. This is useful in functions that return matrices that do not depend on an AutoDiffScalar argument (e.g. a function with a constant output), while it is desired that information about the number of derivatives is preserved.
mat | matrix, for which the derivative vectors of the elements will be resized |
scalar | scalar to match the derivative size vector against. |
Eigen::VectorXd spatialForceInFrameToJointTorque | ( | const RigidBodyTree * | tree, |
const KinematicsCache< double > & | rigid_body_state, | ||
const RigidBodyFrame * | frame, | ||
const Eigen::Matrix< double, 6, 1 > & | force | ||
) |
spatialForceInFrameToJointTorque
helper function for rigid body force elements. todo: move this into RigidBodyTree?
std::shared_ptr<AffineSystem<NullVector, System::template StateVector, System::template InputVector> > Drake::timeInvariantLQR | ( | const System & | sys, |
const typename System::template StateVector< double > & | x0, | ||
const typename System::template InputVector< double > & | u0, | ||
const Eigen::MatrixXd & | Q, | ||
const Eigen::MatrixXd & | R | ||
) |
const Eigen::Matrix<ScalarType, Rows, 1>& Drake::toEigen | ( | const Eigen::Matrix< ScalarType, Rows, 1 > & | vec | ) |
constexpr int Drake::totalSizeAtCompileTime | ( | ) |
Determine the total size at compile time of a number of arguments based on their SizeAtCompileTime static members.
constexpr Eigen::DenseIndex Drake::totalSizeAtRunTime | ( | ) |
Determine the total size at runtime of a number of arguments using their size() methods (base case).
Eigen::DenseIndex Drake::totalSizeAtRunTime | ( | const Eigen::MatrixBase< Head > & | head, |
const Tail &... | tail | ||
) |
Determine the total size at runtime of a number of arguments using their size() methods (recursive)
|
static |