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,
double effect_range = 0.02);
70 JointLimitConstraint(
double weight,
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions,
double effect_range = 0.02);
73 HebiStatusCode addObjective(HebiIKPtr ik)
const override;
75 Eigen::VectorXd _min_positions;
76 Eigen::VectorXd _max_positions;
81 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
141 using ObjectiveCallback = std::function<void(
const std::vector<double>&, std::array<double, N>&)>;
150 void callCallback(
void*,
size_t num_positions,
const double* positions,
double* errors)
const {
157 std::vector<double> positions_array(num_positions);
158 for (
size_t i = 0; i < num_positions; ++i)
159 positions_array[i] = positions[i];
163 std::array<double, N> errors_array;
164 for (
size_t i = 0; i < N; ++i)
165 errors_array[i] = errors[i];
167 _callback(positions_array, errors_array);
169 for (
size_t i = 0; i < N; ++i)
170 errors[i] = errors_array[i];
174 HebiStatusCode addObjective(HebiIKPtr ik)
const override {
175 return hebiIKAddObjectiveCustom(ik, _weight, N, &custom_objective_callback_wrapper<N>,
176 const_cast<CustomObjective*>(
this));
179 ObjectiveCallback _callback;
190 reinterpret_cast<CustomObjective<T>*
>(user_data)->callCallback(user_data, num_positions, positions, errors);
193 class ActuatorMetadata;
194 class BracketMetadata;
197 class RigidBodyMetadata;
200 Other = HebiRobotModelElementTypeOther,
201 Actuator = HebiRobotModelElementTypeActuator,
202 Bracket = HebiRobotModelElementTypeBracket,
203 Joint = HebiRobotModelElementTypeJoint,
204 Link = HebiRobotModelElementTypeLink,
205 RigidBody = HebiRobotModelElementTypeRigidBody,
211 Output = HebiFrameTypeOutput,
213 Input = HebiFrameTypeInput,
214 Mesh = HebiFrameTypeMesh
227 X5_1 = HebiActuatorTypeX5_1,
228 X5_4 = HebiActuatorTypeX5_4,
229 X5_9 = HebiActuatorTypeX5_9,
230 X8_3 = HebiActuatorTypeX8_3,
231 X8_9 = HebiActuatorTypeX8_9,
232 X8_16 = HebiActuatorTypeX8_16,
233 R8_3 = HebiActuatorTypeR8_3,
234 R8_9 = HebiActuatorTypeR8_9,
235 R8_16 = HebiActuatorTypeR8_16,
236 T5_1 = HebiActuatorTypeT5_1,
237 T5_4 = HebiActuatorTypeT5_4,
238 T5_9 = HebiActuatorTypeT5_9,
239 T8_3 = HebiActuatorTypeT8_3,
240 T8_9 = HebiActuatorTypeT8_9,
241 T8_16 = HebiActuatorTypeT8_16,
242 R25_8 = HebiActuatorTypeR25_8,
243 R25_20 = HebiActuatorTypeR25_20,
244 R25_40 = HebiActuatorTypeR25_40,
245 T25_8 = HebiActuatorTypeT25_8,
246 T25_20 = HebiActuatorTypeT25_20,
247 T25_40 = HebiActuatorTypeT25_40
253 R25 = HebiLinkTypeR25,
254 R25_R8 = HebiLinkTypeR25_R8
283 Custom = HebiEndEffectorTypeCustom,
309 if (elementType() == ElementType::Actuator) {
310 return reinterpret_cast<const ActuatorMetadata*>(
this);
321 if (elementType() == ElementType::Bracket) {
322 return reinterpret_cast<const BracketMetadata*>(
this);
333 if (elementType() == ElementType::Joint) {
334 return reinterpret_cast<const JointMetadata*>(
this);
345 if (elementType() == ElementType::Link) {
346 return reinterpret_cast<const LinkMetadata*>(
this);
357 if (elementType() == ElementType::RigidBody) {
358 return reinterpret_cast<const RigidBodyMetadata*>(
this);
365 const HebiRobotModelElementMetadata&
metadata()
const {
return metadata_; }
368 HebiRobotModelElementMetadata metadata_;
417 float extension()
const {
return metadata().extension_; }
422 float twist()
const {
return metadata().twist_; }
443 HebiRobotModelPtr
const internal_;
450 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective)
const {
451 static_assert(std::is_convertible<T*, Objective*>::value,
452 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
453 return static_cast<const Objective*>(&objective)->addObjective(ik);
459 template<
typename T,
typename... Args>
460 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective,
const Args&... args)
const {
461 static_assert(std::is_convertible<T*, Objective*>::value,
462 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
463 auto res = static_cast<const Objective*>(&objective)->addObjective(ik);
464 if (res != HebiStatusSuccess)
466 return addObjectives(ik, args...);
472 bool tryAdd(HebiRobotModelElementPtr element);
494 static std::unique_ptr<RobotModel> loadHRDF(
const std::string& file);
500 static std::unique_ptr<RobotModel> loadHRDFString(
const std::string&
string);
518 std::unique_ptr<RobotModel> createSubtree(
size_t element_index);
537 void setBaseFrame(const Eigen::Matrix4d& base_frame);
543 Eigen::Matrix4d getBaseFrame() const;
554 size_t getFrameCount(
FrameType frame_type) const;
562 getFrameCount(HebiFrameType frame_type)
const {
563 return getFrameCount(static_cast<FrameType>(frame_type));
570 size_t getDoFCount()
const;
581 std::string getMeshPath(
size_t mesh_frame_index)
const;
596 bool addRigidBody(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
597 const Eigen::Matrix4d& output);
615 [[deprecated(
"Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
bool addJoint(
616 HebiJointType joint_type) {
617 return addJoint(static_cast<JointType>(joint_type));
673 bool addEndEffector(
double x,
double y,
double z);
687 bool addEndEffector(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
688 const Eigen::Matrix4d& output);
701 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getForwardKinematics(
702 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
703 getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
738 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getFK(
739 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
740 getFK(static_cast<FrameType>(frame_type), positions, frames);
762 void getEndEffector(
const Eigen::VectorXd& positions, Eigen::Matrix4d& transform)
const;
770 template<
typename... Args>
772 const Args&... args)
const {
773 return solveIK(initial_positions, result, args...);
790 template<
typename... Args>
791 IKResult solveIK(
const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
const Args&... objectives)
const {
793 auto ik = hebiIKCreate();
797 res.
result = addObjectives(ik, objectives...);
798 if (res.
result != HebiStatusSuccess) {
804 auto positions_array =
new double[initial_positions.size()];
806 Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
807 tmp = initial_positions;
809 auto result_array =
new double[initial_positions.size()];
812 res.
result = hebiIKSolve(ik, internal_, positions_array, result_array,
nullptr);
815 delete[] positions_array;
817 Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
820 delete[] result_array;
839 [[deprecated]]
void getJacobians(HebiFrameType frame_type,
const Eigen::VectorXd& positions,
841 getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
864 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getJ(
865 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
MatrixXdVector& jacobians)
const {
866 getJ(static_cast<FrameType>(frame_type), positions, jacobians);
874 void getJacobianEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
894 void getJEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
904 void getMasses(Eigen::VectorXd& masses)
const;
909 void getMetadata(std::vector<MetadataBase>& metadata)
const;
915 void getMaxSpeeds(Eigen::VectorXd& max_speeds)
const;
921 void getMaxEfforts(Eigen::VectorXd& max_efforts)
const;
929 void getGravCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::Vector3d& gravity,
930 Eigen::VectorXd& comp_torque)
const;
936 void getDynamicCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::VectorXd& cmd_pos,
const Eigen::VectorXd& cmd_vel,
937 const Eigen::VectorXd& cmd_accel, Eigen::VectorXd& comp_torque,
double dt)
const;
ActuatorType
Definition: robot_model.hpp:226
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:188
JointType
Definition: robot_model.hpp:217
LinkType
Definition: robot_model.hpp:250
BracketType
Definition: robot_model.hpp:261
CustomObjective(ObjectiveCallback error_function)
Definition: robot_model.hpp:145
#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:839
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:436
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:864
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:791
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:282
Definition: robot_model.hpp:67
LinkInputType
Definition: robot_model.hpp:257
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:738
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:771
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:428
Allows you to add a custom objective function.
Definition: robot_model.hpp:136
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:701
void callCallback(void *, size_t num_positions, const double *positions, double *errors) const
Definition: robot_model.hpp:150
FrameType
Definition: robot_model.hpp:209
LinkOutputType
Definition: robot_model.hpp:259
Definition: robot_model.hpp:20
std::function< void(const std::vector< double > &, std::array< double, N > &)> ObjectiveCallback
Definition: robot_model.hpp:141
ElementType
Definition: robot_model.hpp:199
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:615
CustomObjective(double weight, ObjectiveCallback error_function)
Definition: robot_model.hpp:146