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>>;
33 virtual HebiStatusCode addObjective(HebiIKPtr ik)
const = 0;
42 HebiStatusCode addObjective(HebiIKPtr ik)
const override;
43 double _weight, _x, _y, _z;
52 HebiStatusCode addObjective(HebiIKPtr ik)
const override;
54 const double _matrix[9];
63 HebiStatusCode addObjective(HebiIKPtr ik)
const override;
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);
73 HebiStatusCode addObjective(HebiIKPtr ik)
const override;
75 Eigen::VectorXd _min_positions;
76 Eigen::VectorXd _max_positions;
80 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
140 using ObjectiveCallback = std::function<void(
const std::vector<double>&, std::array<double, N>&)>;
149 void callCallback(
void*,
size_t num_positions,
const double* positions,
double* errors)
const {
156 std::vector<double> positions_array(num_positions);
157 for (
size_t i = 0; i < num_positions; ++i)
158 positions_array[i] = positions[i];
162 std::array<double, N> errors_array;
163 for (
size_t i = 0; i < N; ++i)
164 errors_array[i] = errors[i];
166 _callback(positions_array, errors_array);
168 for (
size_t i = 0; i < N; ++i)
169 errors[i] = errors_array[i];
173 HebiStatusCode addObjective(HebiIKPtr ik)
const override {
174 return hebiIKAddObjectiveCustom(ik, _weight, N, &custom_objective_callback_wrapper<N>,
175 const_cast<CustomObjective*>(
this));
178 ObjectiveCallback _callback;
189 reinterpret_cast<CustomObjective<T>*
>(user_data)->callCallback(user_data, num_positions, positions, errors);
192 class ActuatorMetadata;
193 class BracketMetadata;
196 class RigidBodyMetadata;
199 Other = HebiRobotModelElementTypeOther,
200 Actuator = HebiRobotModelElementTypeActuator,
201 Bracket = HebiRobotModelElementTypeBracket,
202 Joint = HebiRobotModelElementTypeJoint,
203 Link = HebiRobotModelElementTypeLink,
204 RigidBody = HebiRobotModelElementTypeRigidBody,
210 Output = HebiFrameTypeOutput,
212 Input = HebiFrameTypeInput,
213 Mesh = HebiFrameTypeMesh
226 X5_1 = HebiActuatorTypeX5_1,
227 X5_4 = HebiActuatorTypeX5_4,
228 X5_9 = HebiActuatorTypeX5_9,
229 X8_3 = HebiActuatorTypeX8_3,
230 X8_9 = HebiActuatorTypeX8_9,
231 X8_16 = HebiActuatorTypeX8_16,
232 R8_3 = HebiActuatorTypeR8_3,
233 R8_9 = HebiActuatorTypeR8_9,
234 R8_16 = HebiActuatorTypeR8_16
259 Custom = HebiEndEffectorTypeCustom,
285 if (elementType() == ElementType::Actuator) {
286 return reinterpret_cast<const ActuatorMetadata*>(
this);
297 if (elementType() == ElementType::Bracket) {
298 return reinterpret_cast<const BracketMetadata*>(
this);
309 if (elementType() == ElementType::Joint) {
310 return reinterpret_cast<const JointMetadata*>(
this);
321 if (elementType() == ElementType::Link) {
322 return reinterpret_cast<const LinkMetadata*>(
this);
333 if (elementType() == ElementType::RigidBody) {
334 return reinterpret_cast<const RigidBodyMetadata*>(
this);
341 const HebiRobotModelElementMetadata&
metadata()
const {
return metadata_; }
344 HebiRobotModelElementMetadata metadata_;
393 float extension()
const {
return metadata().extension_; }
398 float twist()
const {
return metadata().twist_; }
419 HebiRobotModelPtr
const internal_;
426 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective)
const {
427 static_assert(std::is_convertible<T*, Objective*>::value,
428 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
429 return static_cast<const Objective*>(&objective)->addObjective(ik);
435 template<
typename T,
typename... Args>
436 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective,
const Args&... args)
const {
437 static_assert(std::is_convertible<T*, Objective*>::value,
438 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
439 auto res = static_cast<const Objective*>(&objective)->addObjective(ik);
440 if (res != HebiStatusSuccess)
442 return addObjectives(ik, args...);
448 bool tryAdd(HebiRobotModelElementPtr element);
470 static std::unique_ptr<RobotModel> loadHRDF(
const std::string& file);
476 static std::unique_ptr<RobotModel> loadHRDFString(
const std::string&
string);
494 std::unique_ptr<RobotModel> createSubtree(
size_t element_index);
513 void setBaseFrame(const Eigen::Matrix4d& base_frame);
519 Eigen::Matrix4d getBaseFrame() const;
530 size_t getFrameCount(
FrameType frame_type) const;
538 getFrameCount(HebiFrameType frame_type)
const {
539 return getFrameCount(static_cast<FrameType>(frame_type));
546 size_t getDoFCount()
const;
557 std::string getMeshPath(
size_t mesh_frame_index)
const;
572 bool addRigidBody(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
573 const Eigen::Matrix4d& output);
591 [[deprecated(
"Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
bool addJoint(
592 HebiJointType joint_type) {
593 return addJoint(static_cast<JointType>(joint_type));
649 bool addEndEffector(
double x,
double y,
double z);
663 bool addEndEffector(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
664 const Eigen::Matrix4d& output);
677 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getForwardKinematics(
678 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
679 getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
714 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getFK(
715 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
716 getFK(static_cast<FrameType>(frame_type), positions, frames);
738 void getEndEffector(
const Eigen::VectorXd& positions, Eigen::Matrix4d& transform)
const;
746 template<
typename... Args>
748 const Args&... args)
const {
749 return solveIK(initial_positions, result, args...);
766 template<
typename... Args>
767 IKResult solveIK(
const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
const Args&... objectives)
const {
769 auto ik = hebiIKCreate();
773 res.
result = addObjectives(ik, objectives...);
774 if (res.
result != HebiStatusSuccess) {
780 auto positions_array =
new double[initial_positions.size()];
782 Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
783 tmp = initial_positions;
785 auto result_array =
new double[initial_positions.size()];
788 res.
result = hebiIKSolve(ik, internal_, positions_array, result_array,
nullptr);
791 delete[] positions_array;
793 Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
796 delete[] result_array;
815 [[deprecated]]
void getJacobians(HebiFrameType frame_type,
const Eigen::VectorXd& positions,
817 getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
840 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getJ(
841 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
MatrixXdVector& jacobians)
const {
842 getJ(static_cast<FrameType>(frame_type), positions, jacobians);
850 void getJacobianEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
870 void getJEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
880 void getMasses(Eigen::VectorXd& masses)
const;
885 void getMetadata(std::vector<MetadataBase>& metadata)
const;
893 void getGravCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::Vector3d& gravity,
894 Eigen::VectorXd& comp_torque)
const;
900 void getDynamicCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::VectorXd& cmd_pos,
const Eigen::VectorXd& cmd_vel,
901 const Eigen::VectorXd& cmd_accel, Eigen::VectorXd& comp_torque,
double dt)
const;
ActuatorType
Definition: robot_model.hpp:225
std::vector< Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > Matrix4dVector
Definition: robot_model.hpp:16
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...
Definition: robot_model.hpp:187
JointType
Definition: robot_model.hpp:216
LinkType
Definition: robot_model.hpp:237
BracketType
Definition: robot_model.hpp:243
CustomObjective(ObjectiveCallback error_function)
Definition: robot_model.hpp:144
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:6
void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
Definition: robot_model.hpp:815
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:412
void getJ(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
Definition: robot_model.hpp:840
IKResult solveIK(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, const Args &... objectives) const
Solves for an inverse kinematics solution given a set of objectives.
Definition: robot_model.hpp:767
Definition: robot_model.hpp:36
static Eigen::VectorXd getGravCompEfforts(const hebi::robot_model::RobotModel &model, const Eigen::VectorXd &, const hebi::GroupFeedback &feedback)
Definition: grav_comp.hpp:36
HebiStatusCode result
Definition: robot_model.hpp:21
EndEffectorType
Definition: robot_model.hpp:258
Definition: robot_model.hpp:67
LinkInputType
Definition: robot_model.hpp:239
void getFK(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
Definition: robot_model.hpp:714
IKResult solveInverseKinematics(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, const Args &... args) const
Solves for an inverse kinematics solution given a set of objectives.
Definition: robot_model.hpp:747
virtual ~Objective()
Definition: robot_model.hpp:30
Definition: robot_model.hpp:57
Definition: robot_model.hpp:26
Definition: robot_model.hpp:46
Rigid Body specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:404
Allows you to add a custom objective function.
Definition: robot_model.hpp:135
void getForwardKinematics(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
Definition: robot_model.hpp:677
void callCallback(void *, size_t num_positions, const double *positions, double *errors) const
Definition: robot_model.hpp:149
FrameType
Definition: robot_model.hpp:208
LinkOutputType
Definition: robot_model.hpp:241
Definition: robot_model.hpp:20
std::function< void(const std::vector< double > &, std::array< double, N > &)> ObjectiveCallback
Definition: robot_model.hpp:140
ElementType
Definition: robot_model.hpp:198
std::vector< MatrixXd, Eigen::aligned_allocator< Eigen::MatrixXd > > MatrixXdVector
Definition: robot_model.hpp:17
bool addJoint(HebiJointType joint_type)
Adds a degree of freedom about the specified axis.
Definition: robot_model.hpp:591
CustomObjective(double weight, ObjectiveCallback error_function)
Definition: robot_model.hpp:145