HEBI C++ API  3.7.0
robot_model.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include "hebi.h"
4 
5 #include <memory>
6 #include <vector>
7 
8 #include "Eigen/Eigen"
9 #include "util.hpp"
10 
11 using namespace Eigen;
12 
13 namespace hebi {
14 namespace robot_model {
15 
16 using Matrix4dVector = std::vector<Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>;
17 using MatrixXdVector = std::vector<MatrixXd, Eigen::aligned_allocator<Eigen::MatrixXd>>;
18 // The result of an IK operation. More fields will be added to this structure
19 // in future API releases.
20 struct IKResult {
21  HebiStatusCode result; // Success or failure
22 };
23 
24 class RobotModel;
25 
26 class Objective {
27  friend RobotModel;
28 
29 public:
30  virtual ~Objective() {}
31 
32 protected:
33  virtual HebiStatusCode addObjective(HebiIKPtr ik) const = 0;
34 };
35 
37 public:
38  EndEffectorPositionObjective(const Eigen::Vector3d&);
39  EndEffectorPositionObjective(double weight, const Eigen::Vector3d&);
40 
41 private:
42  HebiStatusCode addObjective(HebiIKPtr ik) const override;
43  double _weight, _x, _y, _z;
44 };
45 
46 class EndEffectorSO3Objective final : public Objective {
47 public:
48  EndEffectorSO3Objective(const Eigen::Matrix3d&);
49  EndEffectorSO3Objective(double weight, const Eigen::Matrix3d&);
50 
51 private:
52  HebiStatusCode addObjective(HebiIKPtr ik) const override;
53  double _weight;
54  const double _matrix[9];
55 };
56 
57 class EndEffectorTipAxisObjective final : public Objective {
58 public:
59  EndEffectorTipAxisObjective(const Eigen::Vector3d&);
60  EndEffectorTipAxisObjective(double weight, const Eigen::Vector3d&);
61 
62 private:
63  HebiStatusCode addObjective(HebiIKPtr ik) const override;
64  double _weight, _x, _y, _z;
65 };
66 
67 class JointLimitConstraint final : public Objective {
68 public:
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);
71 
72 private:
73  HebiStatusCode addObjective(HebiIKPtr ik) const override;
74  double _weight;
75  Eigen::VectorXd _min_positions;
76  Eigen::VectorXd _max_positions;
77 
78 public:
79  // Allow Eigen member variables:
80  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
81 };
82 
91 template<size_t T>
92 inline void custom_objective_callback_wrapper(void* user_data, size_t num_positions, const double* positions,
93  double* errors);
94 
134 template<size_t N>
135 class CustomObjective final : public Objective {
136 public:
137  // This function is called with the following parameters:
138  // const std::vector<double>& positions
139  // std::array<double, N>& errors (NOTE: FILL THIS IN VIA THE CALLBACK FUNCTION)
140  using ObjectiveCallback = std::function<void(const std::vector<double>&, std::array<double, N>&)>;
141 
142  CustomObjective(ObjectiveCallback error_function) : _weight(1.0f), _callback(error_function) {}
143  CustomObjective(double weight, ObjectiveCallback error_function) : _weight(weight), _callback(error_function) {}
144 
145  // Note -- internal function to be called only from
146  // custom_objective_callback_wrapper.
147  void callCallback(void*, size_t num_positions, const double* positions, double* errors) const {
148  // Note -- the data here is copied to/from the C-style arrays. This isn't
149  // optimally efficient, but allows us to use type-checked C++ vectors and
150  // arrays. For performance critical applications, this could be modified
151  // to support user callbacks using the raw C-style arrays directly.
152 
153  // Process data into C++ structures.
154  std::vector<double> positions_array(num_positions);
155  for (size_t i = 0; i < num_positions; ++i)
156  positions_array[i] = positions[i];
157  // Note -- std::array is not guaranteed to be layout-compatible with a
158  // C-style array, even for POD, so we must copy here it we want the type
159  // safety of std::array.
160  std::array<double, N> errors_array;
161  for (size_t i = 0; i < N; ++i)
162  errors_array[i] = errors[i];
163 
164  _callback(positions_array, errors_array);
165 
166  for (size_t i = 0; i < N; ++i)
167  errors[i] = errors_array[i];
168  }
169 
170 private:
171  HebiStatusCode addObjective(HebiIKPtr ik) const override {
172  return hebiIKAddObjectiveCustom(ik, _weight, N, &custom_objective_callback_wrapper<N>,
173  const_cast<CustomObjective*>(this));
174  }
175  double _weight;
176  ObjectiveCallback _callback;
177 };
178 
184 template<size_t T>
185 inline void custom_objective_callback_wrapper(void* user_data, size_t num_positions, const double* positions,
186  double* errors) {
187  reinterpret_cast<CustomObjective<T>*>(user_data)->callCallback(user_data, num_positions, positions, errors);
188 }
189 
190 class ActuatorMetadata;
191 class BracketMetadata;
192 class JointMetadata;
193 class LinkMetadata;
194 class RigidBodyMetadata;
195 
196 enum class ElementType {
197  Other = HebiRobotModelElementTypeOther,
198  Actuator = HebiRobotModelElementTypeActuator,
199  Bracket = HebiRobotModelElementTypeBracket,
200  Joint = HebiRobotModelElementTypeJoint,
201  Link = HebiRobotModelElementTypeLink,
202  RigidBody = HebiRobotModelElementTypeRigidBody,
203  EndEffector = HebiRobotModelElementTypeEndEffector
204 };
205 
206 enum class FrameType {
207  CenterOfMass = HebiFrameTypeCenterOfMass,
208  Output = HebiFrameTypeOutput,
209  EndEffector = HebiFrameTypeEndEffector,
210  Input = HebiFrameTypeInput,
211  Mesh = HebiFrameTypeMesh
212 };
213 
214 enum class JointType {
215  RotationX = HebiJointTypeRotationX,
216  RotationY = HebiJointTypeRotationY,
217  RotationZ = HebiJointTypeRotationZ,
218  TranslationX = HebiJointTypeTranslationX,
219  TranslationY = HebiJointTypeTranslationY,
220  TranslationZ = HebiJointTypeTranslationZ
221 };
222 
223 enum class ActuatorType {
224  X5_1 = HebiActuatorTypeX5_1,
225  X5_4 = HebiActuatorTypeX5_4,
226  X5_9 = HebiActuatorTypeX5_9,
227  X8_3 = HebiActuatorTypeX8_3,
228  X8_9 = HebiActuatorTypeX8_9,
229  X8_16 = HebiActuatorTypeX8_16,
230  R8_3 = HebiActuatorTypeR8_3,
231  R8_9 = HebiActuatorTypeR8_9,
232  R8_16 = HebiActuatorTypeR8_16
233 };
234 
235 enum class LinkType {
236  X5 = HebiLinkTypeX5,
237  X8 = HebiLinkTypeR8
238 };
239 
240 enum class LinkInputType {
241  RightAngle = HebiLinkInputTypeRightAngle,
242  Inline = HebiLinkInputTypeInline
243 };
244 
245 enum class LinkOutputType {
246  RightAngle = HebiLinkOutputTypeRightAngle,
247  Inline = HebiLinkOutputTypeInline
248 };
249 
250 enum class BracketType {
251  X5LightLeft = HebiBracketTypeX5LightLeft,
252  X5LightRight = HebiBracketTypeX5LightRight,
253  X5HeavyLeftInside = HebiBracketTypeX5HeavyLeftInside,
254  X5HeavyLeftOutside = HebiBracketTypeX5HeavyLeftOutside,
255  X5HeavyRightInside = HebiBracketTypeX5HeavyRightInside,
256  X5HeavyRightOutside = HebiBracketTypeX5HeavyRightOutside,
257  R8LightLeft = HebiBracketTypeR8LightLeft,
258  R8LightRight = HebiBracketTypeR8LightRight,
259  R8HeavyLeftInside = HebiBracketTypeR8HeavyLeftInside,
260  R8HeavyLeftOutside = HebiBracketTypeR8HeavyLeftOutside,
261  R8HeavyRightInside = HebiBracketTypeR8HeavyRightInside,
262  R8HeavyRightOutside = HebiBracketTypeR8HeavyRightOutside
263 };
264 
265 enum class EndEffectorType {
266  Custom = HebiEndEffectorTypeCustom,
267  X5Parallel = HebiEndEffectorTypeX5Parallel,
268  R8Parallel = HebiEndEffectorTypeR8Parallel
269 };
270 
271 
276  friend class RobotModel;
277 public:
278  MetadataBase() = default;
279  MetadataBase(const MetadataBase&) = delete;
280  MetadataBase& operator=(const MetadataBase&) = delete;
281  MetadataBase(MetadataBase&&) = default;
282  MetadataBase& operator=(MetadataBase&&) = default;
283 
285  return static_cast<ElementType>(metadata_.element_type_);
286  }
287 
293  const ActuatorMetadata* asActuator() const {
294  if (elementType() == ElementType::Actuator) {
295  return reinterpret_cast<const ActuatorMetadata*>(this);
296  }
297  return nullptr;
298  }
299 
305  const BracketMetadata* asBracket() const {
306  if (elementType() == ElementType::Bracket) {
307  return reinterpret_cast<const BracketMetadata*>(this);
308  }
309  return nullptr;
310  }
311 
317  const JointMetadata* asJoint() const {
318  if (elementType() == ElementType::Joint) {
319  return reinterpret_cast<const JointMetadata*>(this);
320  }
321  return nullptr;
322  }
323 
329  const LinkMetadata* asLink() const {
330  if (elementType() == ElementType::Link) {
331  return reinterpret_cast<const LinkMetadata*>(this);
332  }
333  return nullptr;
334  }
335 
342  if (elementType() == ElementType::RigidBody) {
343  return reinterpret_cast<const RigidBodyMetadata*>(this);
344  }
345  return nullptr;
346  }
347 
348 protected:
349  // Raw data can only be accessed by the sub classes
350  const HebiRobotModelElementMetadata& metadata() const { return metadata_; }
351 private:
352  HebiRobotModelElementMetadata metadata_;
353 };
354 
359 public:
363  ActuatorType actuatorType() const { return static_cast<ActuatorType>(metadata().actuator_type_); }
364 };
365 
370 public:
374  BracketType bracketType() const { return static_cast<BracketType>(metadata().bracket_type_); }
375 };
376 
380 class JointMetadata : public MetadataBase {
381 public:
385  JointType jointType() const { return static_cast<JointType>(metadata().joint_type_); }
386 };
387 
391 class LinkMetadata : public MetadataBase {
392 public:
396  LinkType linkType() const { return static_cast<LinkType>(metadata().link_type_); }
397 
401  float extension() const { return metadata().extension_; }
402 
406  float twist() const { return metadata().twist_; }
407 };
408 
412 class RigidBodyMetadata : public MetadataBase {};
413 
420 class RobotModel final {
421  friend Objective;
422 
423 private:
427  HebiRobotModelPtr const internal_;
428 
433  template<typename T>
434  HebiStatusCode addObjectives(HebiIKPtr ik, const T& objective) const {
435  static_assert(std::is_convertible<T*, Objective*>::value,
436  "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
437  return static_cast<const Objective*>(&objective)->addObjective(ik);
438  }
439 
443  template<typename T, typename... Args>
444  HebiStatusCode addObjectives(HebiIKPtr ik, const T& objective, Args... args) const {
445  static_assert(std::is_convertible<T*, Objective*>::value,
446  "Must pass arguments of base type hebi::robot_model::Objective to the variable args of solveIK!");
447  auto res = static_cast<const Objective*>(&objective)->addObjective(ik);
448  if (res != HebiStatusSuccess)
449  return res;
450  return addObjectives(ik, args...);
451  }
452 
456  bool tryAdd(HebiRobotModelElementPtr element);
457 
462  RobotModel(HebiRobotModelPtr);
463 
464 public:
465 
466  using ActuatorType [[deprecated ("Replace with hebi::robot_model::ActuatorType")]] = robot_model::ActuatorType;
467  using BracketType [[deprecated ("Replace with hebi::robot_model::BracketType")]] = robot_model::BracketType;
468  using LinkType [[deprecated ("Replace with hebi::robot_model::LinkType")]] = robot_model::LinkType;
469 
474  RobotModel();
475 
479  static std::unique_ptr<RobotModel> loadHRDF(const std::string& file);
480 
485  static std::unique_ptr<RobotModel> loadHRDFString(const std::string& string);
486 
503  std::unique_ptr<RobotModel> createSubtree(size_t element_index);
504 
509  ~RobotModel() noexcept;
510 
522  void setBaseFrame(const Eigen::Matrix4d& base_frame);
523 
528  Eigen::Matrix4d getBaseFrame() const;
529 
539  size_t getFrameCount(FrameType frame_type) const;
540 
546  [[deprecated ("Replaced by hebi::robot_model::RobotModel::getFrameCount(hebi::robot_model::FrameType)")]]
547  size_t getFrameCount(HebiFrameType frame_type) const { return getFrameCount(static_cast<FrameType>(frame_type)); }
548 
553  size_t getDoFCount() const;
554 
564  std::string getMeshPath(size_t mesh_frame_index) const;
565 
579  bool addRigidBody(const Eigen::Matrix4d& com, const Eigen::VectorXd& inertia, double mass,
580  const Eigen::Matrix4d& output);
581 
591  bool addJoint(JointType joint_type);
592 
598  [[deprecated ("Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
599  bool addJoint(HebiJointType joint_type) { return addJoint(static_cast<JointType>(joint_type)); }
600 
607  bool addActuator(robot_model::ActuatorType actuator_type);
608 
625  bool addLink(robot_model::LinkType link_type, double extension, double twist,
626  LinkInputType input_type = LinkInputType::RightAngle,
627  LinkOutputType output_type = LinkOutputType::RightAngle);
628 
635  bool addBracket(robot_model::BracketType bracket_type);
636 
645  bool addEndEffector(EndEffectorType end_effector_type);
654  bool addEndEffector(double x, double y, double z);
668  bool addEndEffector(const Eigen::Matrix4d& com, const Eigen::VectorXd& inertia, double mass,
669  const Eigen::Matrix4d& output);
675  void getForwardKinematics(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
676 
682  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
683  void getForwardKinematics(HebiFrameType frame_type, const Eigen::VectorXd& positions, Matrix4dVector& frames) const {
684  getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
685  }
686 
712  void getFK(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
713 
719  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
720  void getFK(HebiFrameType frame_type, const Eigen::VectorXd& positions, Matrix4dVector& frames) const {
721  getFK(static_cast<FrameType>(frame_type), positions, frames);
722  }
723 
743  void getEndEffector(const Eigen::VectorXd& positions, Eigen::Matrix4d& transform) const;
744 
751  template<typename... Args>
752  IKResult solveInverseKinematics(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
753  Args... args) const {
754  return solveIK(initial_positions, result, args...);
755  }
756 
771  template<typename... Args>
772  IKResult solveIK(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result, Args... objectives) const {
773  // Create a HEBI C library IK object
774  auto ik = hebiIKCreate();
775 
776  // (Try) to add objectives to the IK object
777  IKResult res;
778  res.result = addObjectives(ik, objectives...);
779  if (res.result != HebiStatusSuccess) {
780  hebiIKRelease(ik);
781  return res;
782  }
783 
784  // Transfer/initialize from Eigen to C arrays
785  auto positions_array = new double[initial_positions.size()];
786  {
787  Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
788  tmp = initial_positions;
789  }
790  auto result_array = new double[initial_positions.size()];
791 
792  // Call into C library to solve
793  res.result = hebiIKSolve(ik, internal_, positions_array, result_array, nullptr);
794 
795  // Transfer/cleanup from C arrays to Eigen
796  delete[] positions_array;
797  {
798  Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
799  result = tmp;
800  }
801  delete[] result_array;
802 
803  hebiIKRelease(ik);
804 
805  return res;
806  }
807 
813  void getJacobians(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
814 
820  [[deprecated]]
821  void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const {
822  getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
823  }
824 
838  void getJ(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
839 
845  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
846  void getJ(HebiFrameType frame_type, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const {
847  getJ(static_cast<FrameType>(frame_type), positions, jacobians);
848  }
849 
855  void getJacobianEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
875  void getJEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
876 
885  void getMasses(Eigen::VectorXd& masses) const;
886 
890  void getMetadata(std::vector<MetadataBase>& metadata) const;
891 private:
896 };
897 
898 } // namespace robot_model
899 } // namespace hebi
ActuatorType
Definition: robot_model.hpp:223
IKResult solveInverseKinematics(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... args) const
Solves for an inverse kinematics solution given a set of objectives.
Definition: robot_model.hpp:752
std::vector< Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > Matrix4dVector
Definition: robot_model.hpp:16
const RigidBodyMetadata * asRigidBody() const
View the rigid body specific fields, if this metadata describes a rigid body.
Definition: robot_model.hpp:341
Link specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:391
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:185
const ActuatorMetadata * asActuator() const
View the actuator specific fields, if this metadata describes an actuator.
Definition: robot_model.hpp:293
JointType
Definition: robot_model.hpp:214
JointType jointType() const
Specifies the particular joint type.
Definition: robot_model.hpp:385
LinkType
Definition: robot_model.hpp:235
Definition: arm.cpp:5
const BracketMetadata * asBracket() const
View the bracket specific fields, if this metadata describes a bracket.
Definition: robot_model.hpp:305
BracketType
Definition: robot_model.hpp:250
CustomObjective(ObjectiveCallback error_function)
Definition: robot_model.hpp:142
#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:821
ActuatorType actuatorType() const
Specifies the particular actuator model.
Definition: robot_model.hpp:363
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:420
IKResult solveIK(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args... objectives) const
Solves for an inverse kinematics solution given a set of objectives.
Definition: robot_model.hpp:772
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:846
float twist() const
The twist of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:406
Actuator specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:358
ElementType elementType() const
Definition: robot_model.hpp:284
const JointMetadata * asJoint() const
View the joint specific fields, if this metadata describes a joint.
Definition: robot_model.hpp:317
HebiStatusCode result
Definition: robot_model.hpp:21
EndEffectorType
Definition: robot_model.hpp:265
Definition: robot_model.hpp:67
LinkInputType
Definition: robot_model.hpp:240
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:720
Base class for all metadata. Do not instantiate directly.
Definition: robot_model.hpp:275
virtual ~Objective()
Definition: robot_model.hpp:30
Definition: robot_model.hpp:26
size_t getFrameCount(HebiFrameType frame_type) const
Return the number of frames in the forward kinematics.
Definition: robot_model.hpp:547
Definition: robot_model.hpp:46
Rigid Body specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:412
BracketType bracketType() const
Specifies the particular bracket type.
Definition: robot_model.hpp:374
Allows you to add a custom objective function.
Definition: robot_model.hpp:135
Bracket specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:369
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:683
Joint specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:380
void callCallback(void *, size_t num_positions, const double *positions, double *errors) const
Definition: robot_model.hpp:147
FrameType
Definition: robot_model.hpp:206
LinkOutputType
Definition: robot_model.hpp:245
Definition: robot_model.hpp:20
std::function< void(const std::vector< double > &, std::array< double, N > &)> ObjectiveCallback
Definition: robot_model.hpp:140
float extension() const
The extension of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:401
ElementType
Definition: robot_model.hpp:196
LinkType linkType() const
Specifies the particular link type.
Definition: robot_model.hpp:396
const HebiRobotModelElementMetadata & metadata() const
Definition: robot_model.hpp:350
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:599
CustomObjective(double weight, ObjectiveCallback error_function)
Definition: robot_model.hpp:143
const LinkMetadata * asLink() const
View the link specific fields, if this metadata describes a link.
Definition: robot_model.hpp:329