![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <string>
#include "moveit_pro_types/types.hpp"
Classes | |
struct | moveit_pro_controllers::AdmittanceParameters |
struct | moveit_pro_controllers::AdmittanceState |
struct | moveit_pro_controllers::AdmittanceKinematics |
class | moveit_pro_controllers::Admittance |
Namespaces | |
namespace | moveit_pro_controllers |
Typedefs | |
using | moveit_pro_controllers::ForwardKinematicsFn = std::function< bool(const Eigen::VectorNd &reference_joint_values, const Eigen::VectorNd ¤t_joint_values, AdmittanceState &state)> |
using | moveit_pro_controllers::DiffInverseKinematicsFn = std::function< bool(const Eigen::VectorNd &joint_values, const Eigen::Vector6d &cartesian_delta, Eigen::VectorNd &joint_deltas)> |
Functions | |
Eigen::Vector6d | moveit_pro_controllers::substractGravity (const Eigen::Vector6d &sensor_wrench, const Eigen::Isometry3d &world_pose_sensor, const Eigen::Isometry3d &world_pose_ee, const AdmittanceParameters ¶meters) |