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,
228 X5_1 = HebiActuatorTypeX5_1,
229 X5_4 = HebiActuatorTypeX5_4,
230 X5_9 = HebiActuatorTypeX5_9,
231 X8_3 = HebiActuatorTypeX8_3,
232 X8_9 = HebiActuatorTypeX8_9,
233 X8_16 = HebiActuatorTypeX8_16,
234 R8_3 = HebiActuatorTypeR8_3,
235 R8_9 = HebiActuatorTypeR8_9,
236 R8_16 = HebiActuatorTypeR8_16,
237 T5_1 = HebiActuatorTypeT5_1,
238 T5_4 = HebiActuatorTypeT5_4,
239 T5_9 = HebiActuatorTypeT5_9,
240 T8_3 = HebiActuatorTypeT8_3,
241 T8_9 = HebiActuatorTypeT8_9,
242 T8_16 = HebiActuatorTypeT8_16,
243 R25_8 = HebiActuatorTypeR25_8,
244 R25_20 = HebiActuatorTypeR25_20,
245 R25_40 = HebiActuatorTypeR25_40,
246 T25_8 = HebiActuatorTypeT25_8,
247 T25_20 = HebiActuatorTypeT25_20,
248 T25_40 = HebiActuatorTypeT25_40
254 R25 = HebiLinkTypeR25,
255 R25_R8 = HebiLinkTypeR25_R8
284 Custom = HebiEndEffectorTypeCustom,
310 if (elementType() == ElementType::Actuator) {
311 return reinterpret_cast<const ActuatorMetadata*>(
this);
322 if (elementType() == ElementType::Bracket) {
323 return reinterpret_cast<const BracketMetadata*>(
this);
334 if (elementType() == ElementType::Joint) {
335 return reinterpret_cast<const JointMetadata*>(
this);
346 if (elementType() == ElementType::Link) {
347 return reinterpret_cast<const LinkMetadata*>(
this);
358 if (elementType() == ElementType::RigidBody) {
359 return reinterpret_cast<const RigidBodyMetadata*>(
this);
366 const HebiRobotModelElementMetadata&
metadata()
const {
return metadata_; }
369 HebiRobotModelElementMetadata metadata_;
418 float extension()
const {
return metadata().extension_; }
423 float twist()
const {
return metadata().twist_; }
444 HebiRobotModelPtr
const internal_;
451 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective)
const {
452 static_assert(std::is_convertible<T*, Objective*>::value,
453 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
454 return static_cast<const Objective*>(&objective)->addObjective(ik);
460 template<
typename T,
typename... Args>
461 HebiStatusCode addObjectives(HebiIKPtr ik,
const T& objective,
const Args&... args)
const {
462 static_assert(std::is_convertible<T*, Objective*>::value,
463 "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
464 auto res = static_cast<const Objective*>(&objective)->addObjective(ik);
465 if (res != HebiStatusSuccess)
467 return addObjectives(ik, args...);
473 bool tryAdd(HebiRobotModelElementPtr element);
495 static std::unique_ptr<RobotModel> loadHRDF(
const std::string& file);
501 static std::unique_ptr<RobotModel> loadHRDFString(
const std::string&
string);
519 std::unique_ptr<RobotModel> createSubtree(
size_t element_index);
538 void setBaseFrame(const Eigen::Matrix4d& base_frame);
544 Eigen::Matrix4d getBaseFrame() const;
555 size_t getFrameCount(
FrameType frame_type) const;
563 getFrameCount(HebiFrameType frame_type)
const {
564 return getFrameCount(static_cast<FrameType>(frame_type));
571 size_t getDoFCount()
const;
582 std::string getMeshPath(
size_t mesh_frame_index)
const;
597 bool addRigidBody(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
598 const Eigen::Matrix4d& output);
616 [[deprecated(
"Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
bool addJoint(
617 HebiJointType joint_type) {
618 return addJoint(static_cast<JointType>(joint_type));
674 bool addEndEffector(
double x,
double y,
double z);
688 bool addEndEffector(
const Eigen::Matrix4d& com,
const Eigen::VectorXd& inertia,
double mass,
689 const Eigen::Matrix4d& output);
702 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getForwardKinematics(
703 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
704 getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
739 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getFK(
740 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
Matrix4dVector& frames)
const {
741 getFK(static_cast<FrameType>(frame_type), positions, frames);
763 void getEndEffector(
const Eigen::VectorXd& positions, Eigen::Matrix4d& transform)
const;
771 template<
typename... Args>
773 const Args&... args)
const {
774 return solveIK(initial_positions, result, args...);
791 template<
typename... Args>
792 IKResult solveIK(
const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
const Args&... objectives)
const {
794 auto ik = hebiIKCreate();
798 res.
result = addObjectives(ik, objectives...);
799 if (res.
result != HebiStatusSuccess) {
805 result.resize(initial_positions.size());
808 res.
result = hebiIKSolve(ik, internal_, initial_positions.data(), result.data(),
nullptr);
827 [[deprecated]]
void getJacobians(HebiFrameType frame_type,
const Eigen::VectorXd& positions,
829 getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
852 [[deprecated(
"Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
void getJ(
853 HebiFrameType frame_type,
const Eigen::VectorXd& positions,
MatrixXdVector& jacobians)
const {
854 getJ(static_cast<FrameType>(frame_type), positions, jacobians);
862 void getJacobianEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
882 void getJEndEffector(
const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian)
const;
894 void getMasses(Eigen::VectorXd& masses)
const;
902 void getPayloads(Eigen::VectorXd& payloads)
const noexcept;
911 double getPayload(
size_t end_effector_index)
const;
921 bool setPayloads(
const Eigen::VectorXd& payloads);
931 bool setPayload(
size_t end_effector_index,
double payload);
941 Eigen::Vector3d getPayloadCenterOfMass(
size_t end_effector_index);
954 void setPayloadCenterOfMass(
size_t end_effector_index,
const Eigen::Vector3d& com);
959 void getMetadata(std::vector<MetadataBase>& metadata)
const;
965 void getMaxSpeeds(Eigen::VectorXd& max_speeds)
const;
971 void getMaxEfforts(Eigen::VectorXd& max_efforts)
const;
979 void getGravCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::Vector3d& gravity,
980 Eigen::VectorXd& comp_torque)
const;
986 void getDynamicCompEfforts(
const Eigen::VectorXd& angles,
const Eigen::VectorXd& cmd_pos,
const Eigen::VectorXd& cmd_vel,
987 const Eigen::VectorXd& cmd_accel, Eigen::VectorXd& comp_torque,
double dt)
const;
ActuatorType
Definition: robot_model.hpp:227
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:218
LinkType
Definition: robot_model.hpp:251
BracketType
Definition: robot_model.hpp:262
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:827
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:437
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:852
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:792
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:283
Definition: robot_model.hpp:67
LinkInputType
Definition: robot_model.hpp:258
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:739
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:772
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:429
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:702
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:260
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:616
CustomObjective(double weight, ObjectiveCallback error_function)
Definition: robot_model.hpp:146