#include <limits>
#include <unordered_map>
#include <vector>
#include "drake/common/symbolic/expression.h"
#include "drake/common/symbolic/polynomial.h"
#include "drake/common/symbolic/rational_function.h"
#include "drake/common/symbolic/trigonometric_polynomial.h"
#include "drake/multibody/plant/multibody_plant.h"
#include "drake/multibody/tree/mobilizer.h"
#include "drake/multibody/tree/multibody_tree.h"
Classes | |
class | RationalForwardKinematics |
For certain robots (whose joint transforms are algebraic functions of joint variables, for example revolute/prismatic/floating-base joints), we can represent the pose (position, orientation) of each body, as rational functions, namely n(s) / d(s) where both the numerator n(s) and denominator d(s) are polynomials of s, and s is some variable related to the generalized position. More... | |
struct | RationalForwardKinematics::Pose< T > |
This is a proxy for math::RigidTransform. More... | |
Namespaces | |
drake | |
drake::multibody | |