HEBI C++ API  3.15.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  Payload = HebiFrameTypePayload
216 };
217 
218 enum class JointType {
219  RotationX = HebiJointTypeRotationX,
220  RotationY = HebiJointTypeRotationY,
221  RotationZ = HebiJointTypeRotationZ,
222  TranslationX = HebiJointTypeTranslationX,
223  TranslationY = HebiJointTypeTranslationY,
224  TranslationZ = HebiJointTypeTranslationZ
225 };
226 
227 enum class ActuatorType {
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
249 };
250 
251 enum class LinkType {
252  X5 = HebiLinkTypeX5,
253  X8 = HebiLinkTypeR8,
254  R25 = HebiLinkTypeR25,
255  R25_R8 = HebiLinkTypeR25_R8
256 };
257 
258 enum class LinkInputType { RightAngle = HebiLinkInputTypeRightAngle, Inline = HebiLinkInputTypeInline };
259 
260 enum class LinkOutputType { RightAngle = HebiLinkOutputTypeRightAngle, Inline = HebiLinkOutputTypeInline };
261 
262 enum class BracketType {
263  X5LightLeft = HebiBracketTypeX5LightLeft,
264  X5LightRight = HebiBracketTypeX5LightRight,
265  X5HeavyLeftInside = HebiBracketTypeX5HeavyLeftInside,
266  X5HeavyLeftOutside = HebiBracketTypeX5HeavyLeftOutside,
267  X5HeavyRightInside = HebiBracketTypeX5HeavyRightInside,
268  X5HeavyRightOutside = HebiBracketTypeX5HeavyRightOutside,
269  R8LightLeft = HebiBracketTypeR8LightLeft,
270  R8LightRight = HebiBracketTypeR8LightRight,
271  R8HeavyLeftInside = HebiBracketTypeR8HeavyLeftInside,
272  R8HeavyLeftOutside = HebiBracketTypeR8HeavyLeftOutside,
273  R8HeavyRightInside = HebiBracketTypeR8HeavyRightInside,
274  R8HeavyRightOutside = HebiBracketTypeR8HeavyRightOutside,
275  R25LightLeft = HebiBracketTypeR25LightLeft,
276  R25LightRight = HebiBracketTypeR25LightRight,
277  R25HeavyLeftInside = HebiBracketTypeR25HeavyLeftInside,
278  R25HeavyLeftOutside = HebiBracketTypeR25HeavyLeftOutside,
279  R25HeavyRightInside = HebiBracketTypeR25HeavyRightInside,
280  R25HeavyRightOutside = HebiBracketTypeR25HeavyRightOutside
281 };
282 
283 enum class EndEffectorType {
284  Custom = HebiEndEffectorTypeCustom,
285  X5Parallel = HebiEndEffectorTypeX5Parallel,
286  R8Parallel = HebiEndEffectorTypeR8Parallel
287 };
288 
293  friend class RobotModel;
294 
295 public:
296  MetadataBase() = default;
297  MetadataBase(const MetadataBase&) = delete;
298  MetadataBase& operator=(const MetadataBase&) = delete;
299  MetadataBase(MetadataBase&&) = default;
300  MetadataBase& operator=(MetadataBase&&) = default;
301 
302  ElementType elementType() const { return static_cast<ElementType>(metadata_.element_type_); }
303 
309  const ActuatorMetadata* asActuator() const {
310  if (elementType() == ElementType::Actuator) {
311  return reinterpret_cast<const ActuatorMetadata*>(this);
312  }
313  return nullptr;
314  }
315 
321  const BracketMetadata* asBracket() const {
322  if (elementType() == ElementType::Bracket) {
323  return reinterpret_cast<const BracketMetadata*>(this);
324  }
325  return nullptr;
326  }
327 
333  const JointMetadata* asJoint() const {
334  if (elementType() == ElementType::Joint) {
335  return reinterpret_cast<const JointMetadata*>(this);
336  }
337  return nullptr;
338  }
339 
345  const LinkMetadata* asLink() const {
346  if (elementType() == ElementType::Link) {
347  return reinterpret_cast<const LinkMetadata*>(this);
348  }
349  return nullptr;
350  }
351 
358  if (elementType() == ElementType::RigidBody) {
359  return reinterpret_cast<const RigidBodyMetadata*>(this);
360  }
361  return nullptr;
362  }
363 
364 protected:
365  // Raw data can only be accessed by the sub classes
366  const HebiRobotModelElementMetadata& metadata() const { return metadata_; }
367 
368 private:
369  HebiRobotModelElementMetadata metadata_;
370 };
371 
376 public:
380  ActuatorType actuatorType() const { return static_cast<ActuatorType>(metadata().actuator_type_); }
381 };
382 
387 public:
391  BracketType bracketType() const { return static_cast<BracketType>(metadata().bracket_type_); }
392 };
393 
397 class JointMetadata : public MetadataBase {
398 public:
402  JointType jointType() const { return static_cast<JointType>(metadata().joint_type_); }
403 };
404 
408 class LinkMetadata : public MetadataBase {
409 public:
413  LinkType linkType() const { return static_cast<LinkType>(metadata().link_type_); }
414 
418  float extension() const { return metadata().extension_; }
419 
423  float twist() const { return metadata().twist_; }
424 };
425 
429 class RigidBodyMetadata : public MetadataBase {};
430 
437 class RobotModel final {
438  friend Objective;
439 
440 private:
444  HebiRobotModelPtr const internal_;
445 
450  template<typename T>
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);
455  }
456 
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)
466  return res;
467  return addObjectives(ik, args...);
468  }
469 
473  bool tryAdd(HebiRobotModelElementPtr element);
474 
479  RobotModel(HebiRobotModelPtr);
480 
481 public:
482  using ActuatorType [[deprecated("Replace with hebi::robot_model::ActuatorType")]] = robot_model::ActuatorType;
483  using BracketType [[deprecated("Replace with hebi::robot_model::BracketType")]] = robot_model::BracketType;
484  using LinkType [[deprecated("Replace with hebi::robot_model::LinkType")]] = robot_model::LinkType;
485 
490  RobotModel();
491 
495  static std::unique_ptr<RobotModel> loadHRDF(const std::string& file);
496 
501  static std::unique_ptr<RobotModel> loadHRDFString(const std::string& string);
502 
519  std::unique_ptr<RobotModel> createSubtree(size_t element_index);
520 
525  ~RobotModel() noexcept;
526 
538  void setBaseFrame(const Eigen::Matrix4d& base_frame);
539 
544  Eigen::Matrix4d getBaseFrame() const;
545 
555  size_t getFrameCount(FrameType frame_type) const;
556 
562  [[deprecated("Replaced by hebi::robot_model::RobotModel::getFrameCount(hebi::robot_model::FrameType)")]] size_t
563  getFrameCount(HebiFrameType frame_type) const {
564  return getFrameCount(static_cast<FrameType>(frame_type));
565  }
566 
571  size_t getDoFCount() const;
572 
582  std::string getMeshPath(size_t mesh_frame_index) const;
583 
597  bool addRigidBody(const Eigen::Matrix4d& com, const Eigen::VectorXd& inertia, double mass,
598  const Eigen::Matrix4d& output);
599 
609  bool addJoint(JointType joint_type);
610 
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));
619  }
620 
627  bool addActuator(robot_model::ActuatorType actuator_type);
628 
645  bool addLink(robot_model::LinkType link_type, double extension, double twist,
646  LinkInputType input_type = LinkInputType::RightAngle,
647  LinkOutputType output_type = LinkOutputType::RightAngle);
648 
655  bool addBracket(robot_model::BracketType bracket_type);
656 
665  bool addEndEffector(EndEffectorType end_effector_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);
695  void getForwardKinematics(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
696 
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);
705  }
706 
732  void getFK(FrameType, const Eigen::VectorXd& positions, Matrix4dVector& frames) const;
733 
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);
742  }
743 
763  void getEndEffector(const Eigen::VectorXd& positions, Eigen::Matrix4d& transform) const;
764 
771  template<typename... Args>
772  IKResult solveInverseKinematics(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result,
773  const Args&... args) const {
774  return solveIK(initial_positions, result, args...);
775  }
776 
791  template<typename... Args>
792  IKResult solveIK(const Eigen::VectorXd& initial_positions, Eigen::VectorXd& result, const Args&... objectives) const {
793  // Create a HEBI C library IK object
794  auto ik = hebiIKCreate();
795 
796  // (Try) to add objectives to the IK object
797  IKResult res;
798  res.result = addObjectives(ik, objectives...);
799  if (res.result != HebiStatusSuccess) {
800  hebiIKRelease(ik);
801  return res;
802  }
803 
804  // Initialize from Eigen to C arrays
805  result.resize(initial_positions.size());
806 
807  // Call into C library to solve
808  res.result = hebiIKSolve(ik, internal_, initial_positions.data(), result.data(), nullptr);
809 
810  hebiIKRelease(ik);
811 
812  return res;
813  }
814 
820  void getJacobians(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
821 
827  [[deprecated]] void getJacobians(HebiFrameType frame_type, const Eigen::VectorXd& positions,
828  MatrixXdVector& jacobians) const {
829  getJacobians(static_cast<FrameType>(frame_type), positions, jacobians);
830  }
831 
845  void getJ(FrameType, const Eigen::VectorXd& positions, MatrixXdVector& jacobians) const;
846 
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);
855  }
856 
862  void getJacobianEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
882  void getJEndEffector(const Eigen::VectorXd& positions, Eigen::MatrixXd& jacobian) const;
883 
894  void getMasses(Eigen::VectorXd& masses) const;
895 
902  void getPayloads(Eigen::VectorXd& payloads) const noexcept;
903 
911  double getPayload(size_t end_effector_index) const;
912 
921  bool setPayloads(const Eigen::VectorXd& payloads);
922 
931  bool setPayload(size_t end_effector_index, double payload);
932 
941  Eigen::Vector3d getPayloadCenterOfMass(size_t end_effector_index);
942 
954  void setPayloadCenterOfMass(size_t end_effector_index, const Eigen::Vector3d& com);
955 
959  void getMetadata(std::vector<MetadataBase>& metadata) const;
960 
965  void getMaxSpeeds(Eigen::VectorXd& max_speeds) const;
966 
971  void getMaxEfforts(Eigen::VectorXd& max_efforts) const;
972 
973  /*
974  * \param comp_torque A vector which is filled with the torques necessary
975  * to offset the effect of gravity on this robot model. This vector is
976  * resized as necessary inside this function (it is set to have length
977  * equal to the number of degrees of freedom).
978  */
979  void getGravCompEfforts(const Eigen::VectorXd& angles, const Eigen::Vector3d& gravity,
980  Eigen::VectorXd& comp_torque) const;
981 
982  /*
983  * Computes the torques necessary to accelerate the masses within the arm, given the
984  * current configuration.
985  */
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;
988 
989 private:
994 };
995 
996 } // namespace robot_model
997 } // namespace hebi
ActuatorType
Definition: robot_model.hpp:227
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:357
Link specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:408
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:309
JointType
Definition: robot_model.hpp:218
JointType jointType() const
Specifies the particular joint type.
Definition: robot_model.hpp:402
LinkType
Definition: robot_model.hpp:251
Definition: arm.cpp:10
const BracketMetadata * asBracket() const
View the bracket specific fields, if this metadata describes a bracket.
Definition: robot_model.hpp:321
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
ActuatorType actuatorType() const
Specifies the particular actuator model.
Definition: robot_model.hpp:380
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
float twist() const
The twist of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:423
Actuator specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:375
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
ElementType elementType() const
Definition: robot_model.hpp:302
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:333
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
Base class for all metadata. Do not instantiate directly.
Definition: robot_model.hpp:292
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:429
BracketType bracketType() const
Specifies the particular bracket type.
Definition: robot_model.hpp:391
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:386
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
Joint specific view of an element in a RobotModel instance.
Definition: robot_model.hpp:397
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
float extension() const
The extension of the link (e.g., the value specified in invocation of RobotModel::addLink)
Definition: robot_model.hpp:418
ElementType
Definition: robot_model.hpp:199
LinkType linkType() const
Specifies the particular link type.
Definition: robot_model.hpp:413
const HebiRobotModelElementMetadata & metadata() const
Definition: robot_model.hpp:366
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
const LinkMetadata * asLink() const
View the link specific fields, if this metadata describes a link.
Definition: robot_model.hpp:345