11 using namespace Eigen;
14 namespace robot_model {
16 using Matrix4dVector = std::vector<Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>;
17 using MatrixXdVector = std::vector<MatrixXd, Eigen::aligned_allocator<Eigen::MatrixXd>>;
43 double _weight, _x, _y,
_z;
54 const double _matrix[9];
64 double _weight, _x, _y,
_z;
69 JointLimitConstraint(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions);
70 JointLimitConstraint(
double weight,
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions);
80 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
140 using ObjectiveCallback = std::function<void(const std::vector<double>&, std::array<double, N>&)>;
147 void callCallback(
void*,
size_t num_positions,
const double* positions,
double* errors)
const {
154 std::vector<double> positions_array(num_positions);
155 for (
size_t i = 0; i < num_positions; ++i)
156 positions_array[i] = positions[i];
160 std::array<double, N> errors_array;
161 for (
size_t i = 0; i < N; ++i)
162 errors_array[i] = errors[i];
164 _callback(positions_array, errors_array);
166 for (
size_t i = 0; i < N; ++i)
167 errors[i] = errors_array[i];
173 const_cast<CustomObjective*>(
this));
187 reinterpret_cast<CustomObjective<T>*
>(user_data)->callCallback(user_data, num_positions, positions, errors);
284 return static_cast<ElementType>(metadata_.element_type_);
293 if (elementType() == ElementType::Actuator) {
305 if (elementType() == ElementType::Bracket) {
317 if (elementType() == ElementType::Joint) {
329 if (elementType() == ElementType::Link) {
341 if (elementType() == ElementType::RigidBody) {
400 float extension()
const {
return metadata().extension_; }
405 float twist()
const {
return metadata().twist_; }
434 static_assert(std::is_convertible<T*, Objective*>::value,
435 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
436 return static_cast<const Objective*
>(&objective)->addObjective(ik);
442 template<
typename T,
typename... Args>
444 static_assert(std::is_convertible<T*, Objective*>::value,
445 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
446 auto res =
static_cast<const Objective*
>(&objective)->addObjective(ik);
449 return addObjectives(ik, args...);
479 static std::unique_ptr<RobotModel> loadHRDF(
const std::string& file);
498 void setBaseFrame(
const Eigen::Matrix4d& base_frame);
504 Eigen::Matrix4d getBaseFrame()
const;
515 size_t getFrameCount(
FrameType frame_type)
const;
522 [[deprecated (
"Replaced by hebi::robot_model::RobotModel::getFrameCount(hebi::robot_model::FrameType)")]]
529 size_t getDoFCount()
const;
544 bool addRigidBody(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
545 const Eigen::Matrix4d& output);
563 [[deprecated (
"Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
624 [[deprecated (
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
626 getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
661 [[deprecated (
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
663 getFK(static_cast<FrameType>(frame_type), positions, frames);
685 void getEndEffector(
const Eigen::VectorXd& positions, Eigen::Matrix4d& transform)
const;
693 template<
typename... Args>
695 Args... args)
const {
696 return solveIK(initial_positions, result, args...);
713 template<
typename... Args>
714 IKResult solveIK(
const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result, Args... objectives)
const {
720 res.
result = addObjectives(ik, objectives...);
727 auto positions_array =
new double[initial_positions.size()];
729 Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
730 tmp = initial_positions;
732 auto result_array =
new double[initial_positions.size()];
738 delete[] positions_array;
740 Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
743 delete[] result_array;
764 getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
787 [[deprecated (
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
789 getJ(static_cast<FrameType>(frame_type), positions, jacobians);
797 void getJacobianEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
817 void getJEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
827 void getMasses(Eigen::VectorXd& masses)
const;
832 void getMetadata(std::vector<MetadataBase>& metadata)
const;
IKResult solveInverseKinematics(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... args) const
Solves for an inverse kinematics solution given a set of objectives.
Eigen::VectorXd _max_positions
std::vector< Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > Matrix4dVector
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
void custom_objective_callback_wrapper(void *user_data, size_t num_positions, const double *positions, double *errors)
C-style callback wrapper to call into CustomObjective class; this should only be used by the CustomOb...
HebiStatusCode addObjective(HebiIKPtr ik) const override
HebiFrameType
RobotModel Enums.
HebiRobotModelPtr const internal_
CustomObjective(ObjectiveCallback error_function)
#define HEBI_DISABLE_COPY_MOVE(Class)
void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
HebiStatusCode hebiIKAddObjectiveCustom(HebiIKPtr ik, double weight, size_t num_errors, void(*err_fnc)(void *user_data, size_t num_positions, const double *positions, double *errors), void *user_data)
Add a custom objective function to be minimized by the IK solver.
Represents a chain or tree of robot elements (rigid bodies and joints).
Eigen::VectorXd _min_positions
IKResult solveIK(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... objectives) const
Solves for an inverse kinematics solution given a set of objectives.
void getJ(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
struct HebiRobotModel_ * HebiRobotModelPtr
HebiStatusCode addObjectives(HebiIKPtr ik, const T &objective, Args... args) const
HebiIKPtr hebiIKCreate(void)
Inverse Kinematics API.
HebiStatusCode addObjectives(HebiIKPtr ik, const T &objective) const
HebiStatusCode hebiIKSolve(HebiIKPtr ik, HebiRobotModelPtr model, const double *initial_positions, double *ik_solution, void *result_info)
Solves for an inverse kinematics solution that moves the end effector to a given point.
void getFK(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
size_t getFrameCount(HebiFrameType frame_type) const
Return the number of frames in the forward kinematics.
Rigid Body specific view of an element in a RobotModel instance.
Allows you to add a custom objective function.
void getForwardKinematics(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
void callCallback(void *, size_t num_positions, const double *positions, double *errors) const
ObjectiveCallback _callback
struct HebiRobotModelElement_ * HebiRobotModelElementPtr
struct HebiIK_ * HebiIKPtr
std::function< void(const std::vector< double > &, std::array< double, N > &)> ObjectiveCallback
HebiStatusCode
Enum Types.
std::vector< MatrixXd, Eigen::aligned_allocator< Eigen::MatrixXd > > MatrixXdVector
bool addJoint(HebiJointType joint_type)
Adds a degree of freedom about the specified axis.
CustomObjective(double weight, ObjectiveCallback error_function)