|
void | stomp_moveit::utils::kinematics::calculateDampedPseudoInverse (const Eigen::MatrixXd &jacb, Eigen::MatrixXd &jacb_pseudo_inv, double eps=0.011, double lambda=0.01) |
| Calculates the damped pseudo inverse of a matrix using singular value decomposition. More...
|
|
bool | stomp_moveit::utils::kinematics::computeJacobianNullSpace (moveit::core::RobotStatePtr state, std::string group, std::string tool_link, const Eigen::ArrayXi &constrained_dofs, const Eigen::VectorXd &joint_pose, Eigen::MatrixXd &jacb_nullspace) |
| Convenience function to calculate the Jacobian's null space matrix for an under constrained tool cartesian pose. More...
|
|
void | stomp_moveit::utils::kinematics::computeTwist (const Eigen::Affine3d &p0, const Eigen::Affine3d &pf, const Eigen::ArrayXi &nullity, Eigen::VectorXd &twist) |
| Computes the twist vector [vx vy vz wx wy wz]' relative to the current tool coordinate system. The rotational part is composed of the product between the angle times the axis about which it rotates. More...
|
|
boost::optional< moveit_msgs::Constraints > | stomp_moveit::utils::kinematics::curateCartesianConstraints (const moveit_msgs::Constraints &c, const Eigen::Affine3d &ref_pose, double default_pos_tol=0.0005, double default_rot_tol=M_PI) |
| Populates the missing parts of a Cartesian constraints in order to provide a constraint that can be used by the Ik solver. More...
|
|
bool | stomp_moveit::utils::kinematics::decodeCartesianConstraint (moveit::core::RobotModelConstPtr model, const moveit_msgs::Constraints &constraints, Eigen::Affine3d &tool_pose, std::vector< double > &tolerance, std::string target_frame="") |
| Extracts the cartesian data from the constraint message. More...
|
|
bool | stomp_moveit::utils::kinematics::decodeCartesianConstraint (moveit::core::RobotModelConstPtr model, const moveit_msgs::Constraints &constraints, Eigen::Affine3d &tool_pose, Eigen::VectorXd &tolerance, std::string target_frame="") |
| Extracts the cartesian data from the constraint message. More...
|
|
bool | stomp_moveit::utils::kinematics::isCartesianConstraints (const moveit_msgs::Constraints &c) |
| Checks if the constraint structured contains valid data from which a proper cartesian constraint can be produced. More...
|
|
| stomp_moveit::utils::kinematics::MOVEIT_CLASS_FORWARD (IKSolver) |
|
void | stomp_moveit::utils::kinematics::reduceJacobian (const Eigen::MatrixXd &jacb, const std::vector< int > &indices, Eigen::MatrixXd &jacb_reduced) |
| Convenience function to remove entire rows of the Jacobian matrix. More...
|
|
EigenSTL::vector_Affine3d | stomp_moveit::utils::kinematics::sampleCartesianPoses (const moveit_msgs::Constraints &c, const std::vector< double > sampling_resolution={0.05, 0.05, 0.05, M_PI_2, M_PI_2, M_PI_2}, int max_samples=20) |
| Creates cartesian poses in accordance to the constraint and sampling resolution values. More...
|
|
This defines kinematic related utilities.
- Author
- Jorge Nicho
- Date
- June 3, 2016
- Version
- TODO
- Bug:
- No known bugs
- Copyright
- Copyright (c) 2016, Southwest Research Institute
- License
- Software License Agreement (Apache License)
- Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0
- Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
Definition in file kinematics.h.