stomp_moveit::utils::kinematics::KinematicConfig Struct Reference

#include <kinematics.h>

List of all members.

Public Attributes

Constraint Parameters

The constraints on the cartesian goal

Eigen::Array< int, 6, 1 > constrained_dofs = Eigen::Array<int,6,1>::Ones()
 A vector of the form [x y z rx ry rz] filled with 0's and 1's to indicate an unconstrained or fully constrained DOF.
Eigen::Affine3d tool_goal_pose = Eigen::Affine3d::Identity()
 The desired tool pose.
Support Parameters

Used at each iteration until a solution is found

Eigen::ArrayXd joint_update_rates = Eigen::ArrayXd::Zero(1,1)
 The weights to be applied to each update during every iteration [num_dimensions x 1].
Eigen::Array< double, 6, 1 > cartesian_convergence_thresholds = Eigen::Array<double,6,1>::Zero()
 The error margin for each dimension of the twist vector [6 x 1].
Eigen::VectorXd init_joint_pose = Eigen::ArrayXd::Zero(1,1)
 Seed joint pose [num_dimension x 1].
int max_iterations = 100
 The maximum number of iterations that the algorithm will run until convergence is reached.
Null Space Parameters

Used in exploding the task manifold null space

Eigen::ArrayXd null_proj_weights = Eigen::ArrayXd::Zero(1,1)
 Weights to be applied to the null space vector.
Eigen::VectorXd null_space_vector = Eigen::VectorXd::Zero(1)
 Null space vector that is used to exploit the Jacobian's null space.

Detailed Description

Definition at line 59 of file kinematics.h.


Member Data Documentation

Eigen::Array<double,6,1> stomp_moveit::utils::kinematics::KinematicConfig::cartesian_convergence_thresholds = Eigen::Array<double,6,1>::Zero()

The error margin for each dimension of the twist vector [6 x 1].

Definition at line 72 of file kinematics.h.

Eigen::Array<int,6,1> stomp_moveit::utils::kinematics::KinematicConfig::constrained_dofs = Eigen::Array<int,6,1>::Ones()

A vector of the form [x y z rx ry rz] filled with 0's and 1's to indicate an unconstrained or fully constrained DOF.

Definition at line 64 of file kinematics.h.

Eigen::VectorXd stomp_moveit::utils::kinematics::KinematicConfig::init_joint_pose = Eigen::ArrayXd::Zero(1,1)

Seed joint pose [num_dimension x 1].

Definition at line 73 of file kinematics.h.

The weights to be applied to each update during every iteration [num_dimensions x 1].

Definition at line 71 of file kinematics.h.

The maximum number of iterations that the algorithm will run until convergence is reached.

Definition at line 74 of file kinematics.h.

Eigen::ArrayXd stomp_moveit::utils::kinematics::KinematicConfig::null_proj_weights = Eigen::ArrayXd::Zero(1,1)

Weights to be applied to the null space vector.

Definition at line 79 of file kinematics.h.

Eigen::VectorXd stomp_moveit::utils::kinematics::KinematicConfig::null_space_vector = Eigen::VectorXd::Zero(1)

Null space vector that is used to exploit the Jacobian's null space.

Definition at line 80 of file kinematics.h.

The desired tool pose.

Definition at line 66 of file kinematics.h.


The documentation for this struct was generated from the following file:


stomp_moveit
Author(s): Jorge Nicho
autogenerated on Sat Jun 8 2019 19:24:01