HEBI C++ API  3.13.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, double effect_range = 0.02);
70  JointLimitConstraint(double weight, const Eigen::VectorXd& min_positions, const Eigen::VectorXd& max_positions, double effect_range = 0.02);
71 
72 private:
73  HebiStatusCode addObjective(HebiIKPtr ik) const override;
74  double _weight;
75  Eigen::VectorXd _min_positions;
76  Eigen::VectorXd _max_positions;
77  double _effect_range;
78 
79 public:
80  // Allow Eigen member variables:
81  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 };
83 
92 template<size_t T>
93 inline void custom_objective_callback_wrapper(void* user_data, size_t num_positions, const double* positions,
94  double* errors);
95 
135 template<size_t N>
136 class CustomObjective final : public Objective {
137 public:
138  // This function is called with the following parameters:
139  // const std::vector<double>& positions
140  // std::array<double, N>& errors (NOTE: FILL THIS IN VIA THE CALLBACK FUNCTION)
141  using ObjectiveCallback = std::function<void(const std::vector<double>&, std::array<double, N>&)>;
142 
143  CustomObjective(CustomObjective&) = delete;
144  CustomObjective(CustomObjective&&) = delete;
145  CustomObjective(ObjectiveCallback error_function) : _weight(1.0f), _callback(error_function) {}
146  CustomObjective(double weight, ObjectiveCallback error_function) : _weight(weight), _callback(error_function) {}
147 
148  // Note -- internal function to be called only from
149  // custom_objective_callback_wrapper.
150  void callCallback(void*, size_t num_positions, const double* positions, double* errors) const {
151  // Note -- the data here is copied to/from the C-style arrays. This isn't
152  // optimally efficient, but allows us to use type-checked C++ vectors and
153  // arrays. For performance critical applications, this could be modified
154  // to support user callbacks using the raw C-style arrays directly.
155 
156  // Process data into C++ structures.
157  std::vector<double> positions_array(num_positions);
158  for (size_t i = 0; i < num_positions; ++i)
159  positions_array[i] = positions[i];
160  // Note -- std::array is not guaranteed to be layout-compatible with a
161  // C-style array, even for POD, so we must copy here it we want the type
162  // safety of std::array.
163  std::array<double, N> errors_array;
164  for (size_t i = 0; i < N; ++i)
165  errors_array[i] = errors[i];
166 
167  _callback(positions_array, errors_array);
168 
169  for (size_t i = 0; i < N; ++i)
170  errors[i] = errors_array[i];
171  }
172 
173 private:
174  HebiStatusCode addObjective(HebiIKPtr ik) const override {
175  return hebiIKAddObjectiveCustom(ik, _weight, N, &custom_objective_callback_wrapper<N>,
176  const_cast<CustomObjective*>(this));
177  }
178  double _weight;
179  ObjectiveCallback _callback;
180 };
181 
187 template<size_t T>
188 inline void custom_objective_callback_wrapper(void* user_data, size_t num_positions, const double* positions,
189  double* errors) {
190  reinterpret_cast<CustomObjective<T>*>(user_data)->callCallback(user_data, num_positions, positions, errors);
191 }
192 
193 class ActuatorMetadata;
194 class BracketMetadata;
195 class JointMetadata;
196 class LinkMetadata;
197 class RigidBodyMetadata;
198 
199 enum class ElementType {
200  Other = HebiRobotModelElementTypeOther,
201  Actuator = HebiRobotModelElementTypeActuator,
202  Bracket = HebiRobotModelElementTypeBracket,
203  Joint = HebiRobotModelElementTypeJoint,
204  Link = HebiRobotModelElementTypeLink,
205  RigidBody = HebiRobotModelElementTypeRigidBody,
206  EndEffector = HebiRobotModelElementTypeEndEffector
207 };
208 
209 enum class FrameType {
210  CenterOfMass = HebiFrameTypeCenterOfMass,
211  Output = HebiFrameTypeOutput,
212  EndEffector = HebiFrameTypeEndEffector,
213  Input = HebiFrameTypeInput,
214  Mesh = HebiFrameTypeMesh
215 };
216 
217 enum class JointType {
218  RotationX = HebiJointTypeRotationX,
219  RotationY = HebiJointTypeRotationY,
220  RotationZ = HebiJointTypeRotationZ,
221  TranslationX = HebiJointTypeTranslationX,
222  TranslationY = HebiJointTypeTranslationY,
223  TranslationZ = HebiJointTypeTranslationZ
224 };
225 
226 enum class ActuatorType {
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
248 };
249 
250 enum class LinkType {
251  X5 = HebiLinkTypeX5,
252  X8 = HebiLinkTypeR8,
253  R25 = HebiLinkTypeR25,
254  R25_R8 = HebiLinkTypeR25_R8
255 };
256 
257 enum class LinkInputType { RightAngle = HebiLinkInputTypeRightAngle, Inline = HebiLinkInputTypeInline };
258 
259 enum class LinkOutputType { RightAngle = HebiLinkOutputTypeRightAngle, Inline = HebiLinkOutputTypeInline };
260 
261 enum class BracketType {
262  X5LightLeft = HebiBracketTypeX5LightLeft,
263  X5LightRight = HebiBracketTypeX5LightRight,
264  X5HeavyLeftInside = HebiBracketTypeX5HeavyLeftInside,
265  X5HeavyLeftOutside = HebiBracketTypeX5HeavyLeftOutside,
266  X5HeavyRightInside = HebiBracketTypeX5HeavyRightInside,
267  X5HeavyRightOutside = HebiBracketTypeX5HeavyRightOutside,
268  R8LightLeft = HebiBracketTypeR8LightLeft,
269  R8LightRight = HebiBracketTypeR8LightRight,
270  R8HeavyLeftInside = HebiBracketTypeR8HeavyLeftInside,
271  R8HeavyLeftOutside = HebiBracketTypeR8HeavyLeftOutside,
272  R8HeavyRightInside = HebiBracketTypeR8HeavyRightInside,
273  R8HeavyRightOutside = HebiBracketTypeR8HeavyRightOutside,
274  R25LightLeft = HebiBracketTypeR25LightLeft,
275  R25LightRight = HebiBracketTypeR25LightRight,
276  R25HeavyLeftInside = HebiBracketTypeR25HeavyLeftInside,
277  R25HeavyLeftOutside = HebiBracketTypeR25HeavyLeftOutside,
278  R25HeavyRightInside = HebiBracketTypeR25HeavyRightInside,
279  R25HeavyRightOutside = HebiBracketTypeR25HeavyRightOutside
280 };
281 
282 enum class EndEffectorType {
283  Custom = HebiEndEffectorTypeCustom,
284  X5Parallel = HebiEndEffectorTypeX5Parallel,
285  R8Parallel = HebiEndEffectorTypeR8Parallel
286 };
287 
292  friend class RobotModel;
293 
294 public:
295  MetadataBase() = default;
296  MetadataBase(const MetadataBase&) = delete;
297  MetadataBase& operator=(const MetadataBase&) = delete;
298  MetadataBase(MetadataBase&&) = default;
299  MetadataBase& operator=(MetadataBase&&) = default;
300 
301  ElementType elementType() const { return static_cast<ElementType>(metadata_.element_type_); }
302 
308  const ActuatorMetadata* asActuator() const {
309  if (elementType() == ElementType::Actuator) {
310  return reinterpret_cast<const ActuatorMetadata*>(this);
311  }
312  return nullptr;
313  }
314 
320  const BracketMetadata* asBracket() const {
321  if (elementType() == ElementType::Bracket) {
322  return reinterpret_cast<const BracketMetadata*>(this);
323  }
324  return nullptr;
325  }
326 
332  const JointMetadata* asJoint() const {
333  if (elementType() == ElementType::Joint) {
334  return reinterpret_cast<const JointMetadata*>(this);
335  }
336  return nullptr;
337  }
338 
344  const LinkMetadata* asLink() const {
345  if (elementType() == ElementType::Link) {
346  return reinterpret_cast<const LinkMetadata*>(this);
347  }
348  return nullptr;
349  }
350 
357  if (elementType() == ElementType::RigidBody) {
358  return reinterpret_cast<const RigidBodyMetadata*>(this);
359  }
360  return nullptr;
361  }
362 
363 protected:
364  // Raw data can only be accessed by the sub classes
365  const HebiRobotModelElementMetadata& metadata() const { return metadata_; }
366 
367 private:
368  HebiRobotModelElementMetadata metadata_;
369 };
370 
375 public:
379  ActuatorType actuatorType() const { return static_cast<ActuatorType>(metadata().actuator_type_); }
380 };
381 
386 public:
390  BracketType bracketType() const { return static_cast<BracketType>(metadata().bracket_type_); }
391 };
392 
396 class JointMetadata : public MetadataBase {
397 public:
401  JointType jointType() const { return static_cast<JointType>(metadata().joint_type_); }
402 };
403 
407 class LinkMetadata : public MetadataBase {
408 public:
412  LinkType linkType() const { return static_cast<LinkType>(metadata().link_type_); }
413 
417  float extension() const { return metadata().extension_; }
418 
422  float twist() const { return metadata().twist_; }
423 };
424 
428 class RigidBodyMetadata : public MetadataBase {};
429 
436 class RobotModel final {
437  friend Objective;
438 
439 private:
443  HebiRobotModelPtr const internal_;
444 
449  template<typename T>
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);
454  }
455 
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)
465  return res;
466  return addObjectives(ik, args...);
467  }
468 
472  bool tryAdd(HebiRobotModelElementPtr element);
473 
478  RobotModel(HebiRobotModelPtr);
479 
480 public:
481  using ActuatorType [[deprecated("Replace with hebi::robot_model::ActuatorType")]] = robot_model::ActuatorType;
482  using BracketType [[deprecated("Replace with hebi::robot_model::BracketType")]] = robot_model::BracketType;
483  using LinkType [[deprecated("Replace with hebi::robot_model::LinkType")]] = robot_model::LinkType;
484 
489  RobotModel();
490 
494  static std::unique_ptr<RobotModel> loadHRDF(const std::string& file);
495 
500  static std::unique_ptr<RobotModel> loadHRDFString(const std::string& string);
501 
518  std::unique_ptr<RobotModel> createSubtree(size_t element_index);
519 
524  ~RobotModel() noexcept;
525 
537  void setBaseFrame(const Eigen::Matrix4d& base_frame);
538 
543  Eigen::Matrix4d getBaseFrame() const;
544 
554  size_t getFrameCount(FrameType frame_type) const;
555 
561  [[deprecated("Replaced by hebi::robot_model::RobotModel::getFrameCount(hebi::robot_model::FrameType)")]] size_t
562  getFrameCount(HebiFrameType frame_type) const {
563  return getFrameCount(static_cast<FrameType>(frame_type));
564  }
565 
570  size_t getDoFCount() const;
571 
581  std::string getMeshPath(size_t mesh_frame_index) const;
582 
596  bool addRigidBody(const Eigen::Matrix4d& com, const Eigen::VectorXd& inertia, double mass,
597  const Eigen::Matrix4d& output);
598 
608  bool addJoint(JointType joint_type);
609 
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));
618  }
619 
626  bool addActuator(robot_model::ActuatorType actuator_type);
627 
644  bool addLink(robot_model::LinkType link_type, double extension, double twist,
645  LinkInputType input_type = LinkInputType::RightAngle,
646  LinkOutputType output_type = LinkOutputType::RightAngle);
647 
654  bool addBracket(robot_model::BracketType bracket_type);
655 
664  bool addEndEffector(EndEffectorType end_effector_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);
694  void getForwardKinematics(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
695 
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);
704  }
705 
731  void getFK(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
732 
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);
741  }
742 
762  void getEndEffector(const Eigen::VectorXd& positions, Eigen::Matrix4d& transform) const;
763 
770  template<typename... Args>
771  IKResult solveInverseKinematics(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
772  const Args&... args) const {
773  return solveIK(initial_positions, result, args...);
774  }
775 
790  template<typename... Args>
791  IKResult solveIK(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result, const Args&... objectives) const {
792  // Create a HEBI C library IK object
793  auto ik = hebiIKCreate();
794 
795  // (Try) to add objectives to the IK object
796  IKResult res;
797  res.result = addObjectives(ik, objectives...);
798  if (res.result != HebiStatusSuccess) {
799  hebiIKRelease(ik);
800  return res;
801  }
802 
803  // Transfer/initialize from Eigen to C arrays
804  auto positions_array = new double[initial_positions.size()];
805  {
806  Map<Eigen::VectorXd> tmp(positions_array, initial_positions.size());
807  tmp = initial_positions;
808  }
809  auto result_array = new double[initial_positions.size()];
810 
811  // Call into C library to solve
812  res.result = hebiIKSolve(ik, internal_, positions_array, result_array, nullptr);
813 
814  // Transfer/cleanup from C arrays to Eigen
815  delete[] positions_array;
816  {
817  Map<Eigen::VectorXd> tmp(result_array, initial_positions.size());
818  result = tmp;
819  }
820  delete[] result_array;
821 
822  hebiIKRelease(ik);
823 
824  return res;
825  }
826 
832  void getJacobians(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
833 
839  [[deprecated]] void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd& positions,
840  MatrixXdVector& jacobians) const {
841  getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
842  }
843 
857  void getJ(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
858 
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);
867  }
868 
874  void getJacobianEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
894  void getJEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
895 
904  void getMasses(Eigen::VectorXd& masses) const;
905 
909  void getMetadata(std::vector<MetadataBase>& metadata) const;
910 
915  void getMaxSpeeds(Eigen::VectorXd& max_speeds) const;
916 
921  void getMaxEfforts(Eigen::VectorXd& max_efforts) const;
922 
923  /*
924  * \param comp_torque A vector which is filled with the torques necessary
925  * to offset the effect of gravity on this robot model. This vector is
926  * resized as necessary inside this function (it is set to have length
927  * equal to the number of degrees of freedom).
928  */
929  void getGravCompEfforts(const Eigen::VectorXd& angles, const Eigen::Vector3d& gravity,
930  Eigen::VectorXd& comp_torque) const;
931 
932  /*
933  * Computes the torques necessary to accelerate the masses within the arm, given the
934  * current configuration.
935  */
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;
938 
939 private:
944 };
945 
946 } // namespace robot_model
947 } // namespace hebi
ActuatorType
Definition: robot_model.hpp:226
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:356
Link specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:407
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
const ActuatorMetadata * asActuator() const
View the actuator specific fields, if this metadata describes an actuator.
Definition: robot_model.hpp:308
JointType
Definition: robot_model.hpp:217
JointType jointType() const
Specifies the particular joint type.
Definition: robot_model.hpp:401
LinkType
Definition: robot_model.hpp:250
Definition: arm.cpp:10
const BracketMetadata * asBracket() const
View the bracket specific fields, if this metadata describes a bracket.
Definition: robot_model.hpp:320
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
ActuatorType actuatorType() const
Specifies the particular actuator model.
Definition: robot_model.hpp:379
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
float twist() const
The twist of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:422
Actuator specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:374
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
ElementType elementType() const
Definition: robot_model.hpp:301
static Eigen::VectorXd getGravCompEfforts(const hebi::robot_model::RobotModel &model, const Eigen::VectorXd &, const hebi::GroupFeedback &feedback)
Definition: grav_comp.hpp:36
const JointMetadata * asJoint() const
View the joint specific fields, if this metadata describes a joint.
Definition: robot_model.hpp:332
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
Base class for all metadata. Do not instantiate directly.
Definition: robot_model.hpp:291
virtual ~Objective()
Definition: robot_model.hpp:30
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
BracketType bracketType() const
Specifies the particular bracket type.
Definition: robot_model.hpp:390
Allows you to add a custom objective function.
Definition: robot_model.hpp:136
Bracket specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:385
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
Joint specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:396
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
float extension() const
The extension of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:417
ElementType
Definition: robot_model.hpp:199
LinkType linkType() const
Specifies the particular link type.
Definition: robot_model.hpp:412
const HebiRobotModelElementMetadata & metadata() const
Definition: robot_model.hpp:365
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
const LinkMetadata * asLink() const
View the link specific fields, if this metadata describes a link.
Definition: robot_model.hpp:344