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