|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
#include <moveit_pro_base/robot_model/robot_model.hpp>#include <moveit_pro_base/robot_state/robot_state.hpp>#include <tl_expected/expected.hpp>#include <functional>#include "cartesian_planning/types.hpp"

Classes | |
| struct | cartesian_planning::PathIKOptions |
Namespaces | |
| namespace | cartesian_planning |
Typedefs | |
| using | cartesian_planning::NullspaceOverrideFunction = std::function< Eigen::VectorXd(const Eigen::VectorXd ¤t_nullspace_component, const Eigen::VectorXd ¤t_joint_values)> |
| Function signature for a custom nullspace task. | |
Enumerations | |
| enum class | cartesian_planning::TipConstraint { cartesian_planning::kPositionOnly , cartesian_planning::kPositionAndOrientation } |
| Possible task-space constraints when solving kinematics for a path. More... | |
Functions | |
| tl::expected< JointSpacePath, ErrorType > | cartesian_planning::pathIK (moveit_pro::base::RobotState &robot_state, const moveit_pro::base::JointModelGroup &group, const std::vector< const moveit_pro::base::LinkModel * > &tip_links, const Path &reference_path, const PathIKOptions &options) |
| Computes the incremental Inverse Kinematics over a given Cartesian path, for multiple tips. | |
| tl::expected< JointSpacePath, ErrorType > | cartesian_planning::pathIK (moveit_pro::base::RobotState &robot_state, const moveit_pro::base::JointModelGroup &group, const moveit_pro::base::LinkModel &tip_link, const Path &reference_path, const PathIKOptions &options) |
| Computes the incremental Inverse Kinematics over a given Cartesian path, for a single tip. | |
Variables | |
| constexpr double | cartesian_planning::kDefaultPathIkTranslationalStep = 0.001 |
| constexpr double | cartesian_planning::kDefaultPathIkAngularStep = 0.001 |