Contains parameters for the family of differential inverse kinematics function overloads below, each named DoDifferentialInverseKinematics().
#include <drake/multibody/inverse_kinematics/differential_inverse_kinematics.h>
Public Member Functions | |
| DifferentialInverseKinematicsParameters (int num_positions, std::optional< int > num_velocities=std::nullopt) | |
| Constructor. More... | |
| void | AddLinearVelocityConstraint (const std::shared_ptr< solvers::LinearConstraint > constraint) |
| Adds a linear velocity constraint. More... | |
| void | ClearLinearVelocityConstraints () |
| Clears all linear velocity constraints. More... | |
| const solvers::SolverOptions & | get_solver_options () const |
| Provides const access to read the solver options. More... | |
| solvers::SolverOptions & | get_mutable_solver_options () |
| Provides mutable access to change the solver options, e.g., to tune for speed vs accuracy. More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
| DifferentialInverseKinematicsParameters (const DifferentialInverseKinematicsParameters &)=default | |
| DifferentialInverseKinematicsParameters & | operator= (const DifferentialInverseKinematicsParameters &)=default |
| DifferentialInverseKinematicsParameters (DifferentialInverseKinematicsParameters &&)=default | |
| DifferentialInverseKinematicsParameters & | operator= (DifferentialInverseKinematicsParameters &&)=default |
Getters. | |
| double | get_time_step () const |
| int | get_num_positions () const |
| int | get_num_velocities () const |
| const VectorX< double > & | get_nominal_joint_position () const |
| const MatrixX< double > & | get_joint_centering_gain () const |
| const Vector6< bool > & | get_end_effector_velocity_flag () const |
| const std::optional< std::pair< VectorX< double >, VectorX< double > > > & | get_joint_position_limits () const |
| const std::optional< std::pair< VectorX< double >, VectorX< double > > > & | get_joint_velocity_limits () const |
| const std::optional< std::pair< VectorX< double >, VectorX< double > > > & | get_joint_acceleration_limits () const |
| double | get_maximum_scaling_to_report_stuck () const |
| double | get_end_effector_angular_speed_limit () const |
| const std::optional< std::pair< Eigen::Vector3d, Eigen::Vector3d > > & | get_end_effector_translational_velocity_limits () const |
| const std::vector< std::shared_ptr< solvers::LinearConstraint > > & | get_linear_velocity_constraints () const |
Setters. | |
| void | set_time_step (double dt) |
Sets time step to dt. More... | |
| void | set_nominal_joint_position (const Eigen::Ref< const VectorX< double >> &nominal_joint_position) |
| Sets the nominal joint position. More... | |
| void | set_end_effector_velocity_flag (const Vector6< bool > &flag_E) |
| Sets the end effector flags in the body frame. More... | |
| void | set_joint_centering_gain (const MatrixX< double > &K) |
| Sets the joint centering gain, K, so that the joint centering command is attempting to achieve v_next = N⁺(q) * K * (q_nominal - q_current). More... | |
| void | set_joint_position_limits (const std::pair< VectorX< double >, VectorX< double >> &q_bounds) |
| Sets the joint position limits. More... | |
| void | set_joint_velocity_limits (const std::pair< VectorX< double >, VectorX< double >> &v_bounds) |
| Sets the joint velocity limits. More... | |
| void | set_joint_acceleration_limits (const std::pair< VectorX< double >, VectorX< double >> &vd_bounds) |
| Sets the joint acceleration limits. More... | |
| void | set_maximum_scaling_to_report_stuck (double scaling) |
| Sets the threshold for α below which the status returned is DifferentialInverseKinematicsStatus::kStuck. More... | |
| void | set_end_effector_angular_speed_limit (double speed) |
| When calling DoDifferentialInverseKinematics with a desired end-effector pose, this limits the magnitude of the angular velocity vector. More... | |
| void | set_end_effector_translational_velocity_limits (const Eigen::Ref< const Eigen::Vector3d > &lower, const Eigen::Ref< const Eigen::Vector3d > &upper) |
| When calling DoDifferentialInverseKinematics with a desired end-effector pose, this sets limits on the translational velocity. More... | |
|
default |
| DifferentialInverseKinematicsParameters | ( | int | num_positions, |
| std::optional< int > | num_velocities = std::nullopt |
||
| ) |
Constructor.
Initializes the nominal joint position to zeros of size num_positions. The time step is initialized to 1. The end effector flags are initialized to True. The joint centering gains are initialized to zero. All constraints are initialized to nullopt.
| num_positions | Number of generalized positions. |
| num_velocities | Number of generalized velocities (by default it will be set to num_positions). |
| void AddLinearVelocityConstraint | ( | const std::shared_ptr< solvers::LinearConstraint > | constraint | ) |
Adds a linear velocity constraint.
| constraint | A linear constraint on joint velocities. |
| std::exception | if constraint->num_vars != this->get_num_velocities(). |
| void ClearLinearVelocityConstraints | ( | ) |
Clears all linear velocity constraints.
| double get_end_effector_angular_speed_limit | ( | ) | const |
| const std::optional<std::pair<Eigen::Vector3d, Eigen::Vector3d> >& get_end_effector_translational_velocity_limits | ( | ) | const |
| const Vector6<bool>& get_end_effector_velocity_flag | ( | ) | const |
| const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_acceleration_limits | ( | ) | const |
| const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_position_limits | ( | ) | const |
| const std::optional<std::pair<VectorX<double>, VectorX<double> > >& get_joint_velocity_limits | ( | ) | const |
| const std::vector<std::shared_ptr<solvers::LinearConstraint> >& get_linear_velocity_constraints | ( | ) | const |
| double get_maximum_scaling_to_report_stuck | ( | ) | const |
| solvers::SolverOptions& get_mutable_solver_options | ( | ) |
Provides mutable access to change the solver options, e.g., to tune for speed vs accuracy.
| int get_num_positions | ( | ) | const |
| int get_num_velocities | ( | ) | const |
| const solvers::SolverOptions& get_solver_options | ( | ) | const |
Provides const access to read the solver options.
| double get_time_step | ( | ) | const |
|
default |
|
default |
| void set_end_effector_angular_speed_limit | ( | double | speed | ) |
When calling DoDifferentialInverseKinematics with a desired end-effector pose, this limits the magnitude of the angular velocity vector.
| void set_end_effector_translational_velocity_limits | ( | const Eigen::Ref< const Eigen::Vector3d > & | lower, |
| const Eigen::Ref< const Eigen::Vector3d > & | upper | ||
| ) |
When calling DoDifferentialInverseKinematics with a desired end-effector pose, this sets limits on the translational velocity.
| void set_end_effector_velocity_flag | ( | const Vector6< bool > & | flag_E | ) |
Sets the end effector flags in the body frame.
If a spatial velocity flag is set to false, it will not be included in the differential IK formulation.
| void set_joint_acceleration_limits | ( | const std::pair< VectorX< double >, VectorX< double >> & | vd_bounds | ) |
Sets the joint acceleration limits.
| vd_bounds | The first element is the lower bound, and the second is the upper bound. |
| std::exception | if the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element. |
Sets the joint centering gain, K, so that the joint centering command is attempting to achieve v_next = N⁺(q) * K * (q_nominal - q_current).
Sets the joint position limits.
| q_bounds | The first element is the lower bound, and the second is the upper bound. |
| std::exception | if the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element. |
Sets the joint velocity limits.
| v_bounds | The first element is the lower bound, and the second is the upper bound. |
| std::exception | if the first or second element of q_bounds has the wrong dimension or any element of the second element is smaller than its corresponding part in the first element. |
| void set_maximum_scaling_to_report_stuck | ( | double | scaling | ) |
Sets the threshold for α below which the status returned is DifferentialInverseKinematicsStatus::kStuck.
α is the scaling of the commanded spatial velocity, so when α is small, it means that the actual spatial velocity magnitude will be small proportional to the commanded.
Default: 0.01.
| void set_nominal_joint_position | ( | const Eigen::Ref< const VectorX< double >> & | nominal_joint_position | ) |
Sets the nominal joint position.
| std::exception | if nominal_joint_position's dimension differs. |
| void set_time_step | ( | double | dt | ) |
Sets time step to dt.
| std::exception | if dt <= 0. |