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;
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 {
204 };
205 
206 enum class FrameType {
211 };
212 
213 enum class JointType {
220 };
221 
222 enum class ActuatorType {
232 };
233 
234 enum class LinkType {
235  X5 = HebiLinkTypeX5,
237 };
238 
239 enum class LinkInputType {
242 };
243 
244 enum class LinkOutputType {
247 };
248 
249 enum class BracketType {
262 };
263 
264 enum class EndEffectorType {
268 };
269 
270 
275  friend class RobotModel;
276 public:
277  MetadataBase() = default;
278  MetadataBase(const MetadataBase&) = delete;
279  MetadataBase& operator=(const MetadataBase&) = delete;
280  MetadataBase(MetadataBase&&) = default;
281  MetadataBase& operator=(MetadataBase&&) = default;
282 
284  return static_cast<ElementType>(metadata_.element_type_);
285  }
286 
292  const ActuatorMetadata* asActuator() const {
293  if (elementType() == ElementType::Actuator) {
294  return reinterpret_cast<const ActuatorMetadata*>(this);
295  }
296  return nullptr;
297  }
298 
304  const BracketMetadata* asBracket() const {
305  if (elementType() == ElementType::Bracket) {
306  return reinterpret_cast<const BracketMetadata*>(this);
307  }
308  return nullptr;
309  }
310 
316  const JointMetadata* asJoint() const {
317  if (elementType() == ElementType::Joint) {
318  return reinterpret_cast<const JointMetadata*>(this);
319  }
320  return nullptr;
321  }
322 
328  const LinkMetadata* asLink() const {
329  if (elementType() == ElementType::Link) {
330  return reinterpret_cast<const LinkMetadata*>(this);
331  }
332  return nullptr;
333  }
334 
341  if (elementType() == ElementType::RigidBody) {
342  return reinterpret_cast<const RigidBodyMetadata*>(this);
343  }
344  return nullptr;
345  }
346 
347 protected:
348  // Raw data can only be accessed by the sub classes
349  const HebiRobotModelElementMetadata& metadata() const { return metadata_; }
350 private:
352 };
353 
358 public:
362  ActuatorType actuatorType() const { return static_cast<ActuatorType>(metadata().actuator_type_); }
363 };
364 
369 public:
373  BracketType bracketType() const { return static_cast<BracketType>(metadata().bracket_type_); }
374 };
375 
379 class JointMetadata : public MetadataBase {
380 public:
384  JointType jointType() const { return static_cast<JointType>(metadata().joint_type_); }
385 };
386 
390 class LinkMetadata : public MetadataBase {
391 public:
395  LinkType linkType() const { return static_cast<LinkType>(metadata().link_type_); }
396 
400  float extension() const { return metadata().extension_; }
401 
405  float twist() const { return metadata().twist_; }
406 };
407 
411 class RigidBodyMetadata : public MetadataBase {};
412 
419 class RobotModel final {
420  friend Objective;
421 
422 private:
427 
432  template<typename T>
433  HebiStatusCode addObjectives(HebiIKPtr ik, const T& objective) const {
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);
437  }
438 
442  template<typename T, typename... Args>
443  HebiStatusCode addObjectives(HebiIKPtr ik, const T& objective, Args... args) const {
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);
447  if (res != HebiStatusSuccess)
448  return res;
449  return addObjectives(ik, args...);
450  }
451 
455  bool tryAdd(HebiRobotModelElementPtr element);
456 
462 
463 public:
464 
465  using ActuatorType [[deprecated ("Replace with hebi::robot_model::ActuatorType")]] = robot_model::ActuatorType;
466  using BracketType [[deprecated ("Replace with hebi::robot_model::BracketType")]] = robot_model::BracketType;
467  using LinkType [[deprecated ("Replace with hebi::robot_model::LinkType")]] = robot_model::LinkType;
468 
473  RobotModel();
474 
479  static std::unique_ptr<RobotModel> loadHRDF(const std::string& file);
480 
485  ~RobotModel() noexcept;
486 
498  void setBaseFrame(const Eigen::Matrix4d& base_frame);
499 
504  Eigen::Matrix4d getBaseFrame() const;
505 
515  size_t getFrameCount(FrameType frame_type) const;
516 
522  [[deprecated ("Replaced by hebi::robot_model::RobotModel::getFrameCount(hebi::robot_model::FrameType)")]]
523  size_t getFrameCount(HebiFrameType frame_type) const { return getFrameCount(static_cast<FrameType>(frame_type)); }
524 
529  size_t getDoFCount() const;
530 
544  bool addRigidBody(const Eigen::Matrix4d& com, const Eigen::VectorXd& inertia, double mass,
545  const Eigen::Matrix4d& output);
546 
556  bool addJoint(JointType joint_type);
557 
563  [[deprecated ("Replaced by hebi::robot_model::RobotModel::addJoint(hebi::robot_model::JointType)")]]
564  bool addJoint(HebiJointType joint_type) { return addJoint(static_cast<JointType>(joint_type)); }
565 
572  bool addActuator(robot_model::ActuatorType actuator_type);
573 
590  bool addLink(robot_model::LinkType link_type, double extension, double twist,
591  LinkInputType input_type = LinkInputType::RightAngle,
592  LinkOutputType output_type = LinkOutputType::RightAngle);
593 
600  bool addBracket(robot_model::BracketType bracket_type);
601 
610  bool addEndEffector(EndEffectorType end_effector_type);
611 
617  void getForwardKinematics(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
618 
624  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
625  void getForwardKinematics(HebiFrameType frame_type, const Eigen::VectorXd& positions, Matrix4dVector& frames) const {
626  getForwardKinematics(static_cast<FrameType>(frame_type), positions, frames);
627  }
628 
654  void getFK(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
655 
661  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
662  void getFK(HebiFrameType frame_type, const Eigen::VectorXd& positions, Matrix4dVector& frames) const {
663  getFK(static_cast<FrameType>(frame_type), positions, frames);
664  }
665 
685  void getEndEffector(const Eigen::VectorXd& positions, Eigen::Matrix4d& transform) const;
686 
693  template<typename... Args>
694  IKResult solveInverseKinematics(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
695  Args... args) const {
696  return solveIK(initial_positions, result, args...);
697  }
698 
713  template<typename... Args>
714  IKResult solveIK(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result, Args... objectives) const {
715  // Create a HEBI C library IK object
716  auto ik = hebiIKCreate();
717 
718  // (Try) to add objectives to the IK object
719  IKResult res;
720  res.result = addObjectives(ik, objectives...);
721  if (res.result != HebiStatusSuccess) {
722  hebiIKRelease(ik);
723  return res;
724  }
725 
726  // Transfer/initialize from Eigen to C arrays
727  auto positions_array = new double[initial_positions.size()];
728  {
729  Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
730  tmp = initial_positions;
731  }
732  auto result_array = new double[initial_positions.size()];
733 
734  // Call into C library to solve
735  res.result = hebiIKSolve(ik, internal_, positions_array, result_array, nullptr);
736 
737  // Transfer/cleanup from C arrays to Eigen
738  delete[] positions_array;
739  {
740  Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
741  result = tmp;
742  }
743  delete[] result_array;
744 
745  hebiIKRelease(ik);
746 
747  return res;
748  }
749 
755  void getJacobians(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
756 
762  [[deprecated]]
763  void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const {
764  getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
765  }
766 
780  void getJ(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
781 
787  [[deprecated ("Change first argument form HebiFrameType to hebi::robot_model::FrameType")]]
788  void getJ(HebiFrameType frame_type, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const {
789  getJ(static_cast<FrameType>(frame_type), positions, jacobians);
790  }
791 
797  void getJacobianEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
817  void getJEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
818 
827  void getMasses(Eigen::VectorXd& masses) const;
828 
832  void getMetadata(std::vector<MetadataBase>& metadata) const;
833 private:
838 };
839 
840 } // namespace robot_model
841 } // namespace hebi
void getFK(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
void hebiIKRelease(HebiIKPtr ik)
Frees resources created by this inverse kinematics object.
Link specific view of an element in a RobotModel instance.
JointType jointType() const
Specifies the particular joint type.
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...
const ActuatorMetadata * asActuator() const
View the actuator specific fields, if this metadata describes an actuator.
float extension() const
The extension of the link (e.g., the value specified in invocation of RobotModel::addLink) ...
ElementType elementType() const
void getForwardKinematics(HebiFrameType frame_type, const Eigen::VectorXd &positions, Matrix4dVector &frames) const
Generates the forward kinematics for the given robot model.
HebiStatusCode addObjectives(HebiIKPtr ik, const T &objective) const
HebiStatusCode addObjective(HebiIKPtr ik) const override
Definition: arm.cpp:5
HebiFrameType
RobotModel Enums.
Definition: hebi.h:327
HebiStatusCode addObjectives(HebiIKPtr ik, const T &objective, Args...args) const
HebiRobotModelPtr const internal_
CustomObjective(ObjectiveCallback error_function)
#define HEBI_DISABLE_COPY_MOVE(Class)
Definition: util.hpp:6
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).
HebiRobotModelElementMetadata metadata_
std::vector< MatrixXd, Eigen::aligned_allocator< Eigen::MatrixXd >> MatrixXdVector
Definition: robot_model.hpp:17
struct HebiRobotModel_ * HebiRobotModelPtr
Definition: hebi.h:527
Actuator specific view of an element in a RobotModel instance.
HebiJointType
Definition: hebi.h:352
LinkType linkType() const
Specifies the particular link type.
const LinkMetadata * asLink() const
View the link specific fields, if this metadata describes a link.
float twist() const
The twist of the link (e.g., the value specified in invocation of RobotModel::addLink) ...
HebiIKPtr hebiIKCreate(void)
Inverse Kinematics API.
IKResult solveInverseKinematics(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args...args) const
Solves for an inverse kinematics solution given a set of objectives.
void callCallback(void *, size_t num_positions, const double *positions, double *errors) const
BracketType bracketType() const
Specifies the particular bracket type.
void getJ(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
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 getJacobians(HebiFrameType frame_type, const Eigen::VectorXd &positions, MatrixXdVector &jacobians) const
Generates the Jacobian for each frame in the given kinematic tree.
Base class for all metadata. Do not instantiate directly.
const BracketMetadata * asBracket() const
View the bracket specific fields, if this metadata describes a bracket.
const JointMetadata * asJoint() const
View the joint specific fields, if this metadata describes a joint.
Rigid Body specific view of an element in a RobotModel instance.
Allows you to add a custom objective function.
Bracket specific view of an element in a RobotModel instance.
size_t getFrameCount(HebiFrameType frame_type) const
Return the number of frames in the forward kinematics.
const RigidBodyMetadata * asRigidBody() const
View the rigid body specific fields, if this metadata describes a rigid body.
Joint specific view of an element in a RobotModel instance.
IKResult solveIK(const Eigen::VectorXd &initial_positions, Eigen::VectorXd &result, Args...objectives) const
Solves for an inverse kinematics solution given a set of objectives.
ActuatorType actuatorType() const
Specifies the particular actuator model.
std::vector< Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d >> Matrix4dVector
Definition: robot_model.hpp:16
struct HebiRobotModelElement_ * HebiRobotModelElementPtr
Definition: hebi.h:533
struct HebiIK_ * HebiIKPtr
Definition: hebi.h:540
std::function< void(const std::vector< double > &, std::array< double, N > &)> ObjectiveCallback
const HebiRobotModelElementMetadata & metadata() const
HebiStatusCode
Enum Types.
Definition: hebi.h:23
bool addJoint(HebiJointType joint_type)
Adds a degree of freedom about the specified axis.
CustomObjective(double weight, ObjectiveCallback error_function)


hebi_cpp_api_ros
Author(s): Chris Bollinger , Matthew Tesch
autogenerated on Thu May 28 2020 03:14:45