HEBI C++ API  3.16.0
arm.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <set>
4 
5 // HEBI C++ API components
6 #include "group.hpp"
7 #include "group_command.hpp"
8 #include "group_feedback.hpp"
9 #include "robot_config.hpp"
10 #include "robot_model.hpp"
11 #include "trajectory.hpp"
12 
13 // Arm API components
14 #include "arm/end_effector.hpp"
15 #include "arm/goal.hpp"
17 
18 namespace hebi {
19 
20 // Transition code for arm::experimental -> arm
21 namespace experimental {
22  namespace arm = hebi::arm;
23 }
24 
25 namespace arm {
26 
27 // Forward declare for usage in plugin.
28 class Arm;
29 
30 namespace plugin {
31 
48 class Plugin {
49 public:
50  Plugin(const std::string& name) : name_(name) {}
51  virtual ~Plugin() = default;
52 
53  // The name of this plugin
54  std::string name() const { return name_; }
55 
56  // Determines if the plugin's effects are enabled. Note that every
57  // plugin is always invoked by Arm::update, and the plugin itself is
58  // responsible for using this state (and the current ramped "enabled ratio")
59  // to moderate its effect.
60  bool enabled() const { return enabled_; }
61  // Sets enabled state. If "ramp time" > 0, the "enabled" state is immediately
62  // set to the new value, but "enabled_ratio" will change gradually.
63  void setEnabled(bool enabled) { enabled_ = enabled; }
64  // Float value between 0 and 1 of "how enabled" we are as we are
65  // ramping between disabled/enabled state.
66  double enabledRatio() { return enabled_ratio_; }
67  // Set how fast we ramp between enabled and disabled states; returns "false"
68  // if value given is invalid.
69  bool setRampTime(double ramp_time);
70  // How fast we ramp between enabled and disabled states
71  double rampTime() { return ramp_time_; }
72 
73  // Callback which updates state on the arm. Invoked by Arm::update.
74  // Returns `true` on success and `false` otherwise.
75  bool update(Arm&, double dt);
76 
77  // Can be overridden by plugin implementations if necessary; called by `Arm::send`
78  virtual bool send() { return true; }
79 
80  // Override to update any state based on the associated arm.
81  // Invoked when the instance is added to an arm via `Arm::addPlugin`. Returns
82  // "false" if there was an error when attempting to add.
83  virtual bool onAssociated(const Arm&) { return true; }
84 
85 protected:
86  // When the object is created through the "create" factory method,
87  // parameters should be applied in turn. Each parameter should be
88  // validated, and an error returned if they cannot be applied.
89  //
90  // Implementations should override the "applyParameterImpl" functions for parameters of types
91  // they have. The main "applyParameters" function is called to iterate through the config
92  // structure, and should be called by each implementing class' "create" method
93  bool applyParameters(const PluginConfig& config, std::set<std::string> required_parameters);
94  virtual bool applyParameterImpl(const std::string& /*name*/, bool /*value*/) { return false; }
95  virtual bool applyParameterImpl(const std::string& /*name*/, const std::vector<bool>& /*value*/) { return false; }
96  virtual bool applyParameterImpl(const std::string& /*name*/, double /*value*/) { return false; }
97  virtual bool applyParameterImpl(const std::string& /*name*/, const std::vector<double>& /*value*/) { return false; }
98  virtual bool applyParameterImpl(const std::string& /*name*/, const std::string& /*value*/) { return false; }
99  virtual bool applyParameterImpl(const std::string& /*name*/, const std::vector<std::string>& /*value*/) { return false; }
100 
101  // Overridden by plugin implementations, and called by `Plugin::update`
102  virtual bool updateImpl(Arm&, double dt) = 0;
103 
104 private:
105  virtual bool applyParameter(const std::string& name, bool value); // we implement for "enabled"
106  virtual bool applyParameter(const std::string& name, const std::vector<bool>& value) {
107  return applyParameterImpl(name, value);
108  }
109  virtual bool applyParameter(const std::string& name, double value); // we implement for "ramp_time"
110  virtual bool applyParameter(const std::string& name, const std::vector<double>& value) {
111  return applyParameterImpl(name, value);
112  }
113  virtual bool applyParameter(const std::string& name, const std::string& value) {
114  return applyParameterImpl(name, value);
115  }
116  virtual bool applyParameter(const std::string& name, const std::vector<std::string>& value) {
117  return applyParameterImpl(name, value);
118  }
119 
120  // Name of the plugin
121  const std::string name_{};
122  // How long it takes to fully transition enabled state.
123  double ramp_time_{};
124  // Whether the plugin is enabled
125  bool enabled_{true};
126  // Current linear level between off (0) and on (1); updated during `update`
127  double enabled_ratio_{1.};
128 };
129 
130 using Factory = std::function<std::unique_ptr<Plugin>(const PluginConfig&)>;
131 
143 public:
144  static std::unique_ptr<GravityCompensationEffort> create(const PluginConfig&);
145  static std::string pluginTypeName() { return "GravityCompensationEffort"; };
146  bool onAssociated(const Arm& arm) override;
147 
148 protected:
149  // For "imu_feedback_index" and "imu_frame_index"
150  bool applyParameterImpl(const std::string& name, double value) override;
151  // For "imu_rotation_offset"
152  bool applyParameterImpl(const std::string& name, const std::vector<double>& value) override;
153  bool updateImpl(Arm& arm, double dt) override;
154 
155 private:
156  GravityCompensationEffort(const std::string& name) : Plugin(name) {}
157  // Cached helper var
158  Eigen::VectorXd grav_efforts_;
159  // Parameters
160  size_t imu_feedback_index_{};
161  size_t imu_frame_index_{};
162  Eigen::Matrix3d imu_local_transform_{Eigen::Matrix3d::Identity()};
163 };
164 
166 public:
167  static std::unique_ptr<DynamicsCompensationEffort> create(const PluginConfig&);
168  static std::string pluginTypeName() { return "DynamicsCompensationEffort"; };
169  bool onAssociated(const Arm& arm) override;
170 
171 protected:
172  bool updateImpl(Arm& arm, double dt) override;
173 
174 private:
175  DynamicsCompensationEffort(const std::string& name) : Plugin(name) {}
176  // Cached helper var
177  Eigen::VectorXd dyn_efforts_;
178 };
179 
180 class ImpedanceController : public Plugin {
181 public:
182  static std::unique_ptr<ImpedanceController> create(const PluginConfig&);
183  static std::string pluginTypeName() { return "ImpedanceController"; };
184  bool onAssociated(const Arm& arm) override;
185  // Set frame in which gains are defined in to be the end-effector frame, which is otherwise the base frame
186  void setGainsInEndEffectorFrame(bool gains_in_end_effector_frame);
187  // Returns true when gains are in the end-effector frame, and false when they are in the base frame
188  bool gainsInEndEffectorFrame() const { return gains_in_end_effector_frame_; }
189  // Set proportional gains (stiffness) of impedance controller.
190  // Returns "false" if values or size given are invalid.
191  bool setKp(const Eigen::VectorXd& kp);
192  // Returns proportional gains
193  Eigen::VectorXd kp() const { return kp_; }
194  // Set derivative gains (damping) of impedance controller.
195  // Returns "false" if values or size given are invalid.
196  bool setKd(const Eigen::VectorXd& kd);
197  // Returns derivative gains
198  Eigen::VectorXd kd() const { return kd_; }
199  // Set integral gains of impedance controller.
200  // Returns "false" if values or size given are invalid.
201  bool setKi(const Eigen::VectorXd& ki);
202  // Return integral gains
203  Eigen::VectorXd ki() const { return ki_; }
204  // Set caps for integral errors
205  // Returns "false" if values or size given are invalid.
206  bool setIClamp(const Eigen::VectorXd& i_clamp);
207  // Return caps for integral errors, and an empty vector when there are no caps.
208  Eigen::VectorXd iClamp() const { return i_clamp_; }
209 
210 protected:
211  // For "kp", "kd", "ki", and "i_clamp", accessed by set_kp, set_kd, set_ki, and set_i_clamp
212  bool setParam(const std::string& name, const Eigen::VectorXd& value_vector);
213  // For "gains_in_end_effector_frame"
214  bool applyParameterImpl(const std::string& name, bool value) override;
215  // For "kp", "kd", "ki", and "i_clamp"
216  bool applyParameterImpl(const std::string& name, const std::vector<double>& value) override;
217  bool updateImpl(Arm& arm, double dt) override;
218 
219 private:
220  ImpedanceController(const std::string& name) : Plugin(name) {}
221 
222  // Cached helper vars
223 
224  // Current integral error term
225  Eigen::VectorXd i_error_{Eigen::VectorXd::Zero(6)};
226 
227  // Parameters
228 
229  // Translations and Rotations can be specified in the
230  // base frame or in the end effector frame.
231  bool gains_in_end_effector_frame_{}; // Initialized as false (gains are in the base frame)
232  // Impedance Control Gains
233  // NOTE: The gains correspond to:
234  // [ trans_x trans_y trans_z rot_x rot_y rot_z ]
235  Eigen::VectorXd kp_{Eigen::VectorXd::Zero(6)}; // (N/m) or (Nm/rad)
236  Eigen::VectorXd kd_{Eigen::VectorXd::Zero(6)}; // (N/(m/sec)) or (Nm/(rad/sec))
237  Eigen::VectorXd ki_{Eigen::VectorXd::Zero(6)}; // (N/(m*sec)) or (Nm/(rad*sec))
238  Eigen::VectorXd i_clamp_;
239 };
240 
241 class EffortOffset : public Plugin {
242 public:
243  static std::unique_ptr<EffortOffset> create(const PluginConfig&);
244  static std::string pluginTypeName() { return "EffortOffset"; };
245  bool onAssociated(const Arm& arm) override;
246 
247 protected:
248  // For "offset"
249  bool applyParameterImpl(const std::string& name, const std::vector<double>& value) override;
250  bool updateImpl(Arm& arm, double dt) override;
251 
252 private:
253  EffortOffset(const std::string& name) : Plugin(name) {}
254  // Parameters
255  Eigen::VectorXd effort_offsets_{};
256 };
257 
258 class DoubledJoint : public Plugin {
259 public:
260  static std::unique_ptr<DoubledJoint> create(const PluginConfig&);
261  static std::string pluginTypeName() { return "DoubledJoint"; };
262  bool onAssociated(const Arm& arm) override;
263 
264 protected:
265  bool applyParameterImpl(const std::string& name, bool value) override;
266  bool applyParameterImpl(const std::string& name, double value) override;
267  bool applyParameterImpl(const std::string& name, const std::string& value) override;
268  bool updateImpl(Arm& arm, double dt) override;
269 
270 private:
271  DoubledJoint(const std::string& name) : Plugin(name) {}
272  size_t index_{};
273  bool mirror_{};
274  std::string name_;
275  std::string family_;
276  std::shared_ptr<hebi::Group> group_;
277  hebi::GroupCommand cmd_{1};
278 };
279 
280 } // namespace plugin
281 
282 static std::map<std::string, plugin::Factory> ArmPluginMap = {
288 };
289 
290 // A high-level abstraction of a robot arm, coordinating kinematics, control,
291 // and basic motion planning.
292 //
293 // Typical usage is as follows; the robot.cfg file includes information such as
294 // module family and names, HRDFs, gains, etc.
295 //
296 // std::vector<std::string> errors;
297 // auto cfg = RobotConfig::loadConfig("robot.cfg", errors);
298 // if (!cfg)
299 // return; // see contents of "errors"
300 // auto arm = Arm::create(*cfg);
301 // if (!arm)
302 // return; // are modules on network?
303 //
304 // arm->loadGains(cfg->getGains("default"));
305 //
306 // while(true) {
307 // arm->update();
308 // arm->send();
309 // if (some_condition)
310 // arm->setGoal(target_goal);
311 // }
312 //
313 // (Note -- in an actual application, you would want to verify the return
314 // values of many of the functions above to ensure proper operation!)
315 class Arm {
316 public:
318  // Setup functions
320 
321  // Parameters for creating an arm.
322  // Note this structure is deprecated in favor of using HEBI robot config files.
323  struct Params {
324  // The family and names passed to the "lookup" function to find modules
325  // Both are required.
326  std::vector<std::string> families_;
327  std::vector<std::string> names_;
328  // How long a command takes effect for on the robot before expiring, in ms.
329  int32_t command_lifetime_ = 100;
330  // Loop rate, in Hz. This is how fast the arm update loop will nominally
331  // run.
332  double control_frequency_ = 200.f;
333 
334  // The robot description. Either supply the hrdf_file _or_ the robot_model.
335  std::string hrdf_file_;
336  std::shared_ptr<robot_model::RobotModel> robot_model_;
337 
338  // Optionally, supply an end effector to be controlled by the "aux" state of
339  // provided goals.
340  std::shared_ptr<EndEffectorBase> end_effector_;
341 
342  // A function pointer that returns a double representing the current time in
343  // seconds. (Can be overloaded to use, e.g., simulator time)
344  //
345  // The default value uses the steady clock wall time.
346  std::function<double()> get_current_time_s_ = []() {
347  using clock = std::chrono::steady_clock;
348  static const clock::time_point start_time = clock::now();
349  return (std::chrono::duration<double>(clock::now() - start_time)).count();
350  };
351  };
352 
353  // Creates an "Arm" object; uses the RobotConfig file for information about the robot.
354  static std::unique_ptr<Arm> create(const RobotConfig& config);
355  // Creates an "Arm" object; uses the RobotConfig file for information about the robot
356  // and an existing "Lookup" object
357  static std::unique_ptr<Arm> create(const RobotConfig& config, const Lookup& lookup);
358 
359  // Creates an "Arm" object, and puts it into a "weightless" no-goal control
360  // mode.
361  static std::unique_ptr<Arm> create(const Params& params);
362  // Creates an "Arm" object using an existing "Lookup" object, and puts it into a
363  // "weightless" no-goal control mode.
364  static std::unique_ptr<Arm> create(const Params& config, const Lookup& lookup);
365 
366  // Adds the plugin to the arm object, taking ownership of the plugin.
367  bool addPlugin(std::unique_ptr<plugin::Plugin> plugin);
368 
369  // Returns a weak pointer to the first plugin found of the given type, or nullopt
370  // if nothing is found.
371  template<class T>
372  std::weak_ptr<plugin::Plugin> getPluginByType() {
373  for (auto& p : plugins_) {
374  if (dynamic_cast<T*>(p.get()) != nullptr)
375  return p;
376  }
377  return {};
378  }
379 
380  std::weak_ptr<plugin::Plugin> getPluginByName(const std::string& name);
381 
382  // Loads gains from the given .xml file, and sends them to the module. Returns
383  // false if the gains file could not be found, if these is a mismatch in
384  // number of modules, or the modules do not acknowledge receipt of the gains.
385  bool loadGains(const std::string& gains_file);
386 
387  // Sets the end effector.
388  // Note that this is recommended to only do immediately after creating the arm.
389  // If called at a later point, care should be taken to ensure that there are
390  // no concurrent accesses to the Arm class that may access the current end effector.
391  void setEndEffector(std::shared_ptr<arm::EndEffectorBase> ee);
392 
394  // Accessors
396 
397  // Returns the number of modules / DoF in the arm
398  size_t size() const { return group_->size(); }
399 
400  // Returns the internal group. Not necessary for most use cases.
401  const Group& group() const { return *group_; }
402  // Returns the (non-const) internal group. Not necessary for most use cases.
403  // Use with care, as modifying the properties of the underlying group while
404  // using the arm may result in undefined behavior.
405  Group& group() { return *group_; }
406 
407  // Returns the internal robot model. Not necessary for most use cases.
408  const robot_model::RobotModel& robotModel() const { return *robot_model_; }
409  // Returns the (non-const) internal robot model. Not necessary for most use cases.
410  // Use with care, as modifying the properties of the underlying robot model while
411  // using the arm may result in undefined behavior.
412  robot_model::RobotModel& robotModel() { return *robot_model_; }
413 
414  // Returns the velocity limits used for trajectory generation.
415  const Eigen::VectorXd& velocityLimits() const { return vel_limits_; }
416 
417  // Returns the acceleration limits used for trajectory generation.
418  const Eigen::VectorXd& accelerationLimits() const { return accel_limits_; }
419 
420  // Returns the currently active internal trajectory. Not necessary for most
421  // use cases.
422  // Returns 'nullptr' if there is no active trajectory.
423  const trajectory::Trajectory* trajectory() const { return trajectory_.get(); }
424 
425  // Returns the end effector object, if given. Not necessary for most use
426  // cases.
427  // Returns 'nullptr' if there is no end effector.
428  const EndEffectorBase* endEffector() const { return end_effector_.get(); }
429  // Returns the end effector object, if given. Not necessary for most use
430  // cases.
431  // Returns 'nullptr' if there is no end effector.
432  // Use with care, as modifying the properties of the underlying end effector while
433  // using the arm may result in undefined behavior.
434  EndEffectorBase* endEffector() { return end_effector_.get(); }
435 
436  // Returns the command last computed by update, or an empty command object
437  // if "update" has never successfully run.
438  const GroupCommand& pendingCommand() const { return command_; }
439  // Returns the command last computed by update, or an empty command object
440  // if "update" has never successfully run. The returned command can be
441  // modified as desired before it is sent to the robot with the send function.
442  GroupCommand& pendingCommand() { return command_; }
443 
444  // Returns the last feedback obtained by update, or an empty feedback object
445  // if "update" has never successfully run.
446  const GroupFeedback& lastFeedback() const { return feedback_; }
447 
449  // Main loop functions
450  //
451  // Typical usage:
452  //
453  // while(true) {
454  // arm->update();
455  // arm->send();
456  // }
458 
459  // Updates feedback and generates the basic command for this timestep.
460  // To retrieve the feedback, call `getLastFeedback()` after this call.
461  // You can modify the command object after calling this.
462  //
463  // Returns 'false' on a connection problem; true on success.
464  bool update();
465 
466  // Sends the command last computed by "update" to the robot arm. Any user
467  // modifications to the command are included.
468  bool send();
469 
471  // Goals
472  //
473  // A goal is a desired (joint angle) position that the arm should reach, and
474  // optionally information about the time it should reach that goal at and the
475  // path (position, velocity, and acceleration waypoints) it should take to
476  // get there.
477  //
478  // The default behavior when a goal is set is for the arm to plan and begin
479  // executing a smooth motion from its current state to this goal, with an
480  // internal heuristic that defines the time at which it will reach the goal.
481  // This immediately overrides any previous goal that was set.
482  //
483  // If there is no "active" goal the arm is set into a mode where it is
484  // actively controlled to be approximately weightless, and can be moved around
485  // by hand easily. This is the default state when the arm is created.
486  //
487  // After reaching the goal, the arm continues to be commanded with the final
488  // joint state of the set goal, and is _not_ implicitly returned to a
489  // "weightless" mode.
490  //
491  // A goal may also define "aux" states to be sent to an end effector
492  // associated with the arm. In this case, the end effector states are
493  // treated as "step functions", immediately being commanded at the timestamp
494  // of the waypoint they are associated with. An empty "aux" goal or "NaN"
495  // defines a "no transition" at the given waypoint.
497 
498  // Set the current goal waypoint(s), immediately replanning to these
499  // location(s) and optionally end effector states.
500  // Goal is a commanded position / velocity.
501  void setGoal(const Goal& goal);
502 
503  // Gets the current position/velocity/acceleration of the system, based either
504  // on the active trajectory (if present), active commands from the previous feedback
505  // packet (if available), or as a last resort the last feedback from the previous
506  // feedback packet.
507  void currentState(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations) const;
508 
509  // Set the state of aux, if added (e.g., end effector). Overrides any
510  // future aux waypoints.
511  template<typename T>
512  void setAuxState(const T& aux_state) {
513  auto aux_size = aux_state.size();
514  if (aux_state.size() > 0) {
515  aux_times_.resize(1);
516  aux_times_[0] = get_current_time_s_();
517  aux_.resize(aux_size, 1);
518  // Replaces 'aux_.leftCols(1) = aux_state;'
519  for (size_t i = 0; i < aux_size; i++) {
520  aux_(i, 0) = aux_state[i];
521  }
522  } else {
523  // Reset aux states
524  aux_.resize(0, 0);
525  aux_times_.resize(0);
526  }
527  }
528 
529  // Returns the progress (from 0 to 1) of the current goal, per the last
530  // update call.
531  //
532  // If we have reached the goal, progress is "1". If there is no active goal,
533  // or we have just begun, progress is "0".
534  double goalProgress() const;
535 
536  // Have we reached the goal? If there is no goal, returns 'false'
537  bool atGoal() const { return goalProgress() >= 1.0; }
538 
539  // Cancels any active goal, returning to a "weightless" state which does not
540  // actively command position or velocity.
541  void cancelGoal();
542 
544  // Helper functions for forward and inverse kinematics.
546 
547  // Use the following joint limits when computing IK
548  // Affects future calls to solveIK**.
549  void setJointLimits(const Eigen::VectorXd& min_positions, const Eigen::VectorXd& max_positions) {
550  kinematics_helper_.setJointLimits(*robot_model_, min_positions, max_positions);
551  }
552 
553  // Do not use joint limits when computing IK
554  // Affects future calls to solveIK**.
556  kinematics_helper_.clearJointLimits();
557  }
558 
559  // Get the end effector (x,y,z) location
560  Eigen::Vector3d FK(const Eigen::VectorXd& positions) const {
561  return kinematics_helper_.FK3Dof(*robot_model_, positions);
562  }
563 
564  // Get the end effector (x,y,z) location and direction, represented by a unit-length vector
565  void FK(const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Vector3d& tip_axis) const {
566  kinematics_helper_.FK5Dof(*robot_model_, positions, xyz_out, tip_axis);
567  }
568 
569  // Get the end effector (x,y,z) location and orientation (represented by a rotation matrix)
570  void FK(const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Matrix3d& orientation) const {
571  kinematics_helper_.FK6Dof(*robot_model_, positions, xyz_out, orientation);
572  }
573 
574  // Return the joint angles to move to a given xyz location
575  Eigen::VectorXd solveIK(const Eigen::VectorXd& initial_positions, const Eigen::Vector3d& target_xyz) const {
576  return kinematics_helper_.solveIK3Dof(*robot_model_, initial_positions, target_xyz);
577  }
578 
579  // Return the joint angles to move to a given xyz location while
580  // pointing a certain direction
581  Eigen::VectorXd solveIK(const Eigen::VectorXd& initial_positions, const Eigen::Vector3d& target_xyz,
582  const Eigen::Vector3d& end_tip) const {
583  return kinematics_helper_.solveIK5Dof(*robot_model_, initial_positions, target_xyz, end_tip);
584  }
585 
586  // Return the joint angles to move to a given xyz location while
587  // pointing a certain direction
588  Eigen::VectorXd solveIK(const Eigen::VectorXd& initial_positions, const Eigen::Vector3d& target_xyz,
589  const Eigen::Matrix3d& orientation) const {
590  return kinematics_helper_.solveIK6Dof(*robot_model_, initial_positions, target_xyz, orientation);
591  }
592 
594  // Helper functions for velocity and acceleration limits used in setGoal
596 
597  void setVelocityLimits(const Eigen::VectorXd& vel_limits) {
598  if (static_cast<size_t>(vel_limits.size()) != size())
599  throw std::invalid_argument("Velocity limits size does not match robot DoF count.");
600  vel_limits_ = vel_limits;
601  }
602 
604  robot_model_->getMaxSpeeds(vel_limits_);
605  }
606 
608  // Set limits to infinity (no limits)
609  vel_limits_ = Eigen::VectorXd::Constant(size(), std::numeric_limits<double>::infinity());
610  }
611 
612  void setAccelerationLimits(const Eigen::VectorXd& accel_limits) {
613  if (static_cast<size_t>(accel_limits.size()) != size())
614  throw std::invalid_argument("Acceleration limits size does not match robot DoF count.");
615  accel_limits_ = accel_limits;
616  }
617 
619  // Set limits to infinity (no limits)
620  accel_limits_ = Eigen::VectorXd::Constant(size(), std::numeric_limits<double>::infinity());
621  }
622 
623 private:
624  // Private arm constructor
625  Arm(std::function<double()> get_current_time_s, std::shared_ptr<Group> group,
626  std::shared_ptr<robot_model::RobotModel> robot_model, std::shared_ptr<EndEffectorBase> end_effector = nullptr)
627  : get_current_time_s_(get_current_time_s),
628  last_time_(get_current_time_s()),
629  group_(std::move(group)),
630  robot_model_(std::move(robot_model)),
631  end_effector_(std::move(end_effector)),
632  pos_(Eigen::VectorXd::Zero(group_->size())),
633  vel_(Eigen::VectorXd::Zero(group_->size())),
634  accel_(Eigen::VectorXd::Zero(group_->size())),
635  vel_limits_(Eigen::VectorXd::Constant(group_->size(), std::numeric_limits<double>::infinity())),
636  accel_limits_(Eigen::VectorXd::Constant(group_->size(), std::numeric_limits<double>::infinity())),
637  feedback_(group_->size()),
638  command_(group_->size()) {
639  // Set velocity limit from robot model
641  }
642 
643  // Optionally uses lookup object internally
644  static std::unique_ptr<Arm> create(const RobotConfig& config, const Lookup* lookup);
645  // Optionally uses lookup object internally
646  static std::unique_ptr<Arm> create(const Params& config, const Lookup* lookup);
647 
648  // Returns the aux state at this point in the trajectory
649  Eigen::VectorXd getAux(double t) const;
650 
651  std::function<double()> get_current_time_s_;
652  double last_time_;
653  std::shared_ptr<Group> group_;
654  std::shared_ptr<robot_model::RobotModel> robot_model_;
655  std::shared_ptr<EndEffectorBase> end_effector_;
656 
657  // The joint angle trajectory for reaching the current goal.
658  std::shared_ptr<trajectory::Trajectory> trajectory_;
659  double trajectory_start_time_{std::numeric_limits<double>::quiet_NaN()};
660  // These are just temporary variables to cache output from
661  // Trajectory::getState.
662  Eigen::VectorXd pos_;
663  Eigen::VectorXd vel_;
664  Eigen::VectorXd accel_;
665 
666  // Along with a trajectory, aux states may be set. These are the last aux
667  // state for each timestep in the trajectory:
668  Eigen::VectorXd aux_times_;
669  Eigen::MatrixXd aux_;
670 
671  // Robot model helpers for FK + IK
672  internal::KinematicsHelper kinematics_helper_;
673 
674  // Velocity and acceleration limits for trajectory generation
675  Eigen::VectorXd vel_limits_;
676  Eigen::VectorXd accel_limits_;
677 
678  hebi::GroupFeedback feedback_;
679  hebi::GroupCommand command_;
680 
681  // Current arm plugins
682  std::vector<std::shared_ptr<plugin::Plugin>> plugins_;
683 
684  friend plugin::DynamicsCompensationEffort;
685 };
686 
687 } // namespace arm
688 } // namespace hebi
void setJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:549
bool setRampTime(double ramp_time)
Definition: arm.cpp:15
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:281
std::function< std::unique_ptr< Plugin >(const PluginConfig &)> Factory
Definition: arm.hpp:130
std::function< double()> get_current_time_s_
Definition: arm.hpp:346
bool loadGains(const std::string &gains_file)
Definition: arm.cpp:679
Definition: plugin_config.hpp:11
virtual bool updateImpl(Arm &, double dt)=0
virtual bool send()
Definition: arm.hpp:78
A list of Feedback objects that can be received from a Group of modules; the size() must match the nu...
Definition: group_feedback.hpp:18
static std::unique_ptr< DynamicsCompensationEffort > create(const PluginConfig &)
Definition: arm.cpp:183
static std::string pluginTypeName()
Definition: arm.hpp:145
static std::unique_ptr< GravityCompensationEffort > create(const PluginConfig &)
Definition: arm.cpp:103
Represents a group of physical HEBI modules, and allows Command, Feedback, and Info objects to be sen...
Definition: group.hpp:106
bool atGoal() const
Definition: arm.hpp:537
static std::string pluginTypeName()
Definition: arm.hpp:261
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:213
void setJointLimits(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: kinematics_helper.cpp:7
static std::unique_ptr< DoubledJoint > create(const PluginConfig &)
Definition: arm.cpp:384
static std::string pluginTypeName()
Definition: arm.hpp:168
Eigen::VectorXd solveIK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: kinematics_helper.cpp:44
GroupCommand & pendingCommand()
Definition: arm.hpp:442
void setVelocityLimits(const Eigen::VectorXd &vel_limits)
Definition: arm.hpp:597
bool update(Arm &, double dt)
Definition: arm.cpp:87
Eigen::VectorXd ki() const
Definition: arm.hpp:203
virtual bool applyParameterImpl(const std::string &, const std::vector< double > &)
Definition: arm.hpp:97
bool applyParameterImpl(const std::string &name, bool value) override
Definition: arm.cpp:410
Eigen::VectorXd solveIK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
Definition: kinematics_helper.cpp:97
void setEnabled(bool enabled)
Definition: arm.hpp:63
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:110
std::vector< std::string > names_
Definition: arm.hpp:327
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:379
EndEffectorBase * endEffector()
Definition: arm.hpp:434
bool setKi(const Eigen::VectorXd &ki)
Definition: arm.cpp:229
Definition: arm.cpp:10
virtual bool applyParameterImpl(const std::string &, double)
Definition: arm.hpp:96
size_t size() const
Definition: arm.hpp:398
robot_model::RobotModel & robotModel()
Definition: arm.hpp:412
virtual bool onAssociated(const Arm &)
Definition: arm.hpp:83
virtual ~Plugin()=default
virtual bool applyParameterImpl(const std::string &, const std::vector< std::string > &)
Definition: arm.hpp:99
std::weak_ptr< plugin::Plugin > getPluginByType()
Definition: arm.hpp:372
Represents a chain or tree of robot elements (rigid bodies and joints).
Definition: robot_model.hpp:437
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:442
Definition: arm.hpp:48
Definition: arm.hpp:323
Eigen::VectorXd kd() const
Definition: arm.hpp:198
static std::unique_ptr< Arm > create(const RobotConfig &config)
Definition: arm.cpp:475
Eigen::VectorXd kp() const
Definition: arm.hpp:193
void FK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Definition: kinematics_helper.cpp:134
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
Definition: arm.hpp:588
Definition: arm.cpp:11
std::shared_ptr< robot_model::RobotModel > robot_model_
Definition: arm.hpp:336
double rampTime()
Definition: arm.hpp:71
Eigen::VectorXd solveIK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
Definition: kinematics_helper.cpp:69
std::string name() const
Definition: arm.hpp:54
std::vector< std::string > families_
Definition: arm.hpp:326
void clearAccelerationLimits()
Definition: arm.hpp:618
bool applyParameterImpl(const std::string &name, double value) override
Definition: arm.cpp:120
void setAuxState(const T &aux_state)
Definition: arm.hpp:512
Definition: arm.hpp:258
bool gainsInEndEffectorFrame() const
Definition: arm.hpp:188
const Eigen::VectorXd & accelerationLimits() const
Definition: arm.hpp:418
bool update()
Definition: arm.cpp:691
int32_t command_lifetime_
Definition: arm.hpp:329
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:196
Eigen::Vector3d FK(const Eigen::VectorXd &positions) const
Definition: arm.hpp:560
Plugin for providing gravity compensating torques for the arm.
Definition: arm.hpp:142
void clearJointLimits()
Definition: arm.hpp:555
bool applyParameters(const PluginConfig &config, std::set< std::string > required_parameters)
Definition: arm.cpp:22
bool enabled() const
Definition: arm.hpp:60
bool setParam(const std::string &name, const Eigen::VectorXd &value_vector)
Definition: arm.cpp:237
const Group & group() const
Definition: arm.hpp:401
const trajectory::Trajectory * trajectory() const
Definition: arm.hpp:423
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: arm.hpp:575
bool setKp(const Eigen::VectorXd &kp)
Definition: arm.cpp:221
void clearVelocityLimits()
Definition: arm.hpp:607
bool applyParameterImpl(const std::string &name, bool value) override
Definition: arm.cpp:242
std::weak_ptr< plugin::Plugin > getPluginByName(const std::string &name)
Definition: arm.cpp:671
Definition: arm.hpp:241
static std::string pluginTypeName()
Definition: arm.hpp:244
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Definition: arm.hpp:570
bool setKd(const Eigen::VectorXd &kd)
Definition: arm.cpp:225
A list of Command objects appropriate for sending to a Group of modules; the size() must match the nu...
Definition: group_command.hpp:19
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:157
double control_frequency_
Definition: arm.hpp:332
void setGainsInEndEffectorFrame(bool gains_in_end_effector_frame)
Definition: arm.cpp:217
static std::string pluginTypeName()
Definition: arm.hpp:183
void currentState(Eigen::VectorXd &positions, Eigen::VectorXd &velocities, Eigen::VectorXd &accelerations) const
Definition: arm.cpp:757
bool addPlugin(std::unique_ptr< plugin::Plugin > plugin)
Definition: arm.cpp:658
void cancelGoal()
Definition: arm.cpp:783
const EndEffectorBase * endEffector() const
Definition: arm.hpp:428
bool applyParameterImpl(const std::string &name, const std::vector< double > &value) override
Definition: arm.cpp:368
double enabledRatio()
Definition: arm.hpp:66
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:361
const GroupCommand & pendingCommand() const
Definition: arm.hpp:438
Eigen::Vector3d FK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions) const
Definition: kinematics_helper.cpp:125
double goalProgress() const
Definition: arm.cpp:771
static std::unique_ptr< EffortOffset > create(const PluginConfig &)
Definition: arm.cpp:354
Definition: arm.hpp:315
const GroupFeedback & lastFeedback() const
Definition: arm.hpp:446
Maintains a registry of network-connected modules and returns Group objects to the user.
Definition: lookup.hpp:24
bool setIClamp(const Eigen::VectorXd &i_clamp)
Definition: arm.cpp:233
static std::unique_ptr< ImpedanceController > create(const PluginConfig &)
Definition: arm.cpp:206
Represents a smooth trajectory through a set of waypoints.
Definition: trajectory.hpp:17
Definition: robot_config.hpp:13
void clearJointLimits()
Definition: kinematics_helper.cpp:37
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:391
Plugin(const std::string &name)
Definition: arm.hpp:50
Group & group()
Definition: arm.hpp:405
virtual bool applyParameterImpl(const std::string &, bool)
Definition: arm.hpp:94
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
Definition: arm.hpp:581
Definition: end_effector.hpp:11
virtual bool applyParameterImpl(const std::string &, const std::string &)
Definition: arm.hpp:98
Definition: goal.hpp:16
void setVelocityLimitsFromModel()
Definition: arm.hpp:603
std::string hrdf_file_
Definition: arm.hpp:335
Eigen::VectorXd iClamp() const
Definition: arm.hpp:208
static std::map< std::string, plugin::Factory > ArmPluginMap
Definition: arm.hpp:282
const Eigen::VectorXd & velocityLimits() const
Definition: arm.hpp:415
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:190
void setAccelerationLimits(const Eigen::VectorXd &accel_limits)
Definition: arm.hpp:612
virtual bool applyParameterImpl(const std::string &, const std::vector< bool > &)
Definition: arm.hpp:95
void setGoal(const Goal &goal)
Definition: arm.cpp:743
std::shared_ptr< EndEffectorBase > end_effector_
Definition: arm.hpp:340
bool send()
Definition: arm.cpp:741
const robot_model::RobotModel & robotModel() const
Definition: arm.hpp:408
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Definition: arm.hpp:565
void FK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Definition: kinematics_helper.cpp:146
void setEndEffector(std::shared_ptr< arm::EndEffectorBase > ee)
Definition: arm.cpp:687