Drake
Drake C++ Documentation
differential_inverse_kinematics_system.h File Reference
#include <limits>
#include <memory>
#include <optional>
#include <string>
#include <utility>
#include <vector>
#include "drake/common/drake_copyable.h"
#include "drake/common/name_value.h"
#include "drake/common/string_unordered_map.h"
#include "drake/planning/collision_checker.h"
#include "drake/planning/dof_mask.h"
#include "drake/planning/joint_limits.h"
#include "drake/solvers/mathematical_program.h"
#include "drake/systems/framework/leaf_system.h"
Include dependency graph for differential_inverse_kinematics_system.h:
This graph shows which files directly or indirectly include this file:

Classes

class  DifferentialInverseKinematicsSystem
 The DifferentialInverseKinematicsSystem takes as input desired cartesian poses (or cartesian velocities) for an arbitrary number of "goal" frames on the robot, and produces a generalized velocity command as output to move the goal frames toward the desired state. More...
 
struct  DifferentialInverseKinematicsSystem::CallbackDetails
 (Internal use only) A group of common arguments relevant to multiple different costs and constraints within the DifferentialInverseKinematicsSystem program formulation. More...
 
class  DifferentialInverseKinematicsSystem::Ingredient
 (Internal use only) A user-provided set of constraint(s) and/or cost(s) for a DifferentialInverseKinematicsSystem recipe, to allow for user customization of the mathematical program formulation. More...
 
class  DifferentialInverseKinematicsSystem::Recipe
 A recipe collects a list of ingredients for DifferentialInverseKinematicsSystem, allowing the user to customize the program being solved. More...
 
class  DifferentialInverseKinematicsSystem::LeastSquaresCost
 Provides a primary DifferentialInverseKinematicsSystem objective to minimize G*| S * (Vd_TGs - Jv_TGs * v_next)|², also known as the "least squares" formulation. More...
 
struct  DifferentialInverseKinematicsSystem::LeastSquaresCost::Config
 
class  DifferentialInverseKinematicsSystem::JointCenteringCost
 Provides a secondary minimization objective. More...
 
struct  DifferentialInverseKinematicsSystem::JointCenteringCost::Config
 
class  DifferentialInverseKinematicsSystem::CartesianPositionLimitConstraint
 Constrains the goal frames to a cartesian bounding box: ∀i p_TG_next_lower ≤ p_TGi + Jv_TGi[3:6] * v_next * Δt ≤ p_TG_next_upper where: More...
 
struct  DifferentialInverseKinematicsSystem::CartesianPositionLimitConstraint::Config
 
class  DifferentialInverseKinematicsSystem::CartesianVelocityLimitConstraint
 Constrains the spatial velocities of the goal frames: ∀i, ∀j ∈ [0, 5]: abs(Jv_TGi * v_next)[j] ≤ V_next_TG_limit[j]. More...
 
struct  DifferentialInverseKinematicsSystem::CartesianVelocityLimitConstraint::Config
 
class  DifferentialInverseKinematicsSystem::CollisionConstraint
 Constrains the collision clearance around the robot to remain above the safety distance: ∀j ϕₛ ≤ ϕⱼ + ∂ϕⱼ/∂q_active * v_next * Δt where: More...
 
struct  DifferentialInverseKinematicsSystem::CollisionConstraint::Config
 
class  DifferentialInverseKinematicsSystem::JointVelocityLimitConstraint
 Constrains the generalized velocity to prevent a commanded velocity that would push the generalized position outside its limits. More...
 
struct  DifferentialInverseKinematicsSystem::JointVelocityLimitConstraint::Config
 

Namespaces

 drake
 
 drake::multibody
 

Typedefs

using SelectDataForCollisionConstraintFunction = std::function< void(const planning::DofMask &active_dof, const planning::RobotClearance &robot_clearance, Eigen::VectorXd *dist_out, Eigen::MatrixXd *ddist_dq_out)>
 (Advanced) Filters clearance data for defining a collision constraint, as used by DifferentialInverseKinematicsSystem::CollisionConstraint. More...