arm.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // HEBI C++ API components
4 #include "hebi_cpp_api/group.hpp"
9 
10 // Arm API components
11 #include "end_effector.hpp"
12 #include "goal.hpp"
13 #include "kinematics_helper.hpp"
14 
15 namespace hebi {
16 namespace experimental {
17 namespace arm {
18 
19 // A high-level abstraction of a robot arm, coordinating kinematics, control,
20 // and basic motion planning.
21 //
22 // Typical usage is:
23 //
24 // arm::Params params;
25 // params.families_ = {"Arm"};
26 // params.names_ = {"J1_base", "J2_shoulder", "J3_elbow", "J4_wrist1", "J5_wrist2", "J6_wrist3"};
27 // params.hrdf_file_ = "my_robot.hrdf"
28 //
29 // auto arm = Arm::create(params);
30 // arm->loadGains("my_robot_gains.xml");
31 //
32 // while(true) {
33 // arm->update();
34 // arm->send();
35 // if (some_condition)
36 // arm->setGoal(target_goal);
37 // }
38 //
39 // (Note -- in an actual application, you would want to verify the return
40 // values of many of the functions above to ensure proper operation!)
41 class Arm {
42 
43 public:
44 
46  // Setup functions
48 
49  // Parameters for creating an arm
50  struct Params {
51  // The family and names passed to the "lookup" function to find modules
52  // Both are required.
53  std::vector<std::string> families_;
54  std::vector<std::string> names_;
55  // How long a command takes effect for on the robot before expiring.
56  int command_lifetime_ = 100;
57  // Loop rate, in Hz. This is how fast the arm update loop will nominally
58  // run.
59  double control_frequency_ = 200.f;
60 
61  // The robot description. Either supply the hrdf_file _or_ the robot_model.
62  std::string hrdf_file_;
63  std::shared_ptr<robot_model::RobotModel> robot_model_;
64 
65  // Optionally, supply an end effector to be controlled by the "aux" state of
66  // provided goals.
67  std::shared_ptr<EndEffectorBase> end_effector_;
68 
69  // A function pointer that returns a double representing the current time in
70  // seconds. (Can be overloaded to use, e.g., simulator time)
71  //
72  // The default value uses the steady clock wall time.
73  std::function<double()> get_current_time_s_ = []() {
74  using clock = std::chrono::steady_clock;
75  static const clock::time_point start_time = clock::now();
76  return (std::chrono::duration<double>(clock::now() - start_time)).count();
77  };
78  };
79 
80  // Creates an "Arm" object, and puts it into a "weightless" no-goal control
81  // mode.
82  static std::unique_ptr<Arm> create(const Params& params);
83 
84  // Loads gains from the given .xml file, and sends them to the module. Returns
85  // false if the gains file could not be found, if these is a mismatch in
86  // number of modules, or the modules do not acknowledge receipt of the gains.
87  bool loadGains(const std::string& gains_file);
88 
90  // Accessors
92 
93  // Returns the number of modules / DoF in the arm
94  size_t size() const { return group_->size(); }
95 
96  // Returns the internal group. Not necessary for most use cases.
97  const Group& group() const { return *group_; }
98 
99  // Returns the internal robot model. Not necessary for most use cases.
100  const robot_model::RobotModel& robotModel() const { return *robot_model_; }
101 
102  // Returns the currently active internal trajectory. Not necessary for most
103  // use cases.
104  // Returns 'nullptr' if there is no active trajectory.
105  const trajectory::Trajectory* trajectory() const { return trajectory_.get(); }
106 
107  // Returns the end effector object, if given. Not necessary for most use
108  // cases.
109  // Returns 'nullptr' if there is no end effector.
110  const EndEffectorBase* endEffector() const { return end_effector_.get(); }
111 
112  // Returns the command last computed by update, or an empty command object
113  // if "update" has never successfully run. The returned command can be
114  // modified as desired before it is sent to the robot with the send function.
116  const GroupCommand& pendingCommand() const { return command_; }
117 
118  // Returns the last feedback obtained by update, or an empty feedback object
119  // if "update" has never successfully run.
120  const GroupFeedback& lastFeedback() const { return feedback_; }
121 
123  // Main loop functions
124  //
125  // Typical usage:
126  //
127  // while(true) {
128  // arm->update();
129  // arm->send();
130  // }
132 
133  // Updates feedback and generates the basic command for this timestep.
134  // To retrieve the feedback, call `getLastFeedback()` after this call.
135  // You can modify the command object after calling this.
136  //
137  // Returns 'false' on a connection problem; true on success.
138  bool update();
139 
140  // Sends the command last computed by "update" to the robot arm. Any user
141  // modifications to the command are included.
142  bool send();
143 
145  // Goals
146  //
147  // A goal is a desired (joint angle) position that the arm should reach, and
148  // optionally information about the time it should reach that goal at and the
149  // path (position, velocity, and acceleration waypoints) it should take to
150  // get there.
151  //
152  // The default behavior when a goal is set is for the arm to plan and begin
153  // executing a smooth motion from its current state to this goal, with an
154  // internal heuristic that defines the time at which it will reach the goal.
155  // This immediately overrides any previous goal that was set.
156  //
157  // If there is no "active" goal the arm is set into a mode where it is
158  // actively controlled to be approximately weightless, and can be moved around
159  // by hand easily. This is the default state when the arm is created.
160  //
161  // After reaching the goal, the arm continues to be commanded with the final
162  // joint state of the set goal, and is _not_ implicitly returned to a
163  // "weightless" mode.
164  //
165  // A goal may also define "aux" states to be sent to an end effector
166  // associated with the arm. In this case, the end effector states are
167  // treated as "step functions", immediately being commanded at the timestamp
168  // of the waypoint they are associated with. An empty "aux" goal or "NaN"
169  // defines a "no transition" at the given waypoint.
171 
172  // Set the current goal waypoint(s), immediately replanning to these
173  // location(s) and optionally end effector states.
174  // Goal is a commanded position / velocity.
175  void setGoal(const Goal& goal);
176 
177  // Set the state of aux, if added (e.g., end effector). Overrides any
178  // future aux waypoints.
179  template<typename T>
180  void setAuxState(const T& aux_state) {
181  auto aux_size = aux_state.size();
182  if (aux_state.size() > 0) {
183  aux_times_.resize(1);
185  aux_.resize(aux_size, 1);
186  // Replaces 'aux_.leftCols(1) = aux_state;'
187  for (size_t i = 0; i < aux_size; i++) {
188  aux_(i, 0) = aux_state[i];
189  }
190  } else {
191  // Reset aux states
192  aux_.resize(0, 0);
193  aux_times_.resize(0);
194  }
195  }
196 
197  // Returns the progress (from 0 to 1) of the current goal, per the last
198  // update call.
199  //
200  // If we have reached the goal, progress is "1". If there is no active goal,
201  // or we have just begun, progress is "0".
202  double goalProgress() const;
203 
204  // Have we reached the goal? If there is no goal, returns 'false'
205  bool atGoal() const { return goalProgress() >= 1.0; }
206 
207  // Cancels any active goal, returning to a "weightless" state which does not
208  // actively command position or velocity.
209  void cancelGoal();
210 
212  // Helper functions for forward and inverse kinematics.
214 
215  // Use the following joint limits when computing IK
216  // Affects future calls to solveIK**.
217  void setJointLimits(const Eigen::VectorXd& min_positions, const Eigen::VectorXd& max_positions) {
218  kinematics_helper_.setJointLimits(*robot_model_, min_positions, max_positions);
219  }
220 
221  // Do not use joint limits when computing IK
222  // Affects future calls to solveIK**.
223  void clearJointLimits(const Eigen::VectorXd& min_positions, const Eigen::VectorXd& max_positions) {
225  }
226 
227  // Get the end effector (x,y,z) location
228  Eigen::Vector3d FK(const Eigen::VectorXd& positions) const {
229  return kinematics_helper_.FK3Dof(*robot_model_, positions);
230  }
231 
232  // Get the end effector (x,y,z) location and direction, represented by a unit-length vector
233  void FK(const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Vector3d& tip_axis) const {
234  kinematics_helper_.FK5Dof(*robot_model_, positions, xyz_out, tip_axis);
235  }
236 
237  // Get the end effector (x,y,z) location and orientation (represented by a rotation matrix)
238  void FK(const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Matrix3d& orientation) const {
239  kinematics_helper_.FK6Dof(*robot_model_, positions, xyz_out, orientation);
240  }
241 
242  // Return the joint angles to move to a given xyz location
243  Eigen::VectorXd solveIK(
244  const Eigen::VectorXd& initial_positions,
245  const Eigen::Vector3d& target_xyz) const {
246  return kinematics_helper_.solveIK3Dof(*robot_model_, initial_positions, target_xyz);
247  }
248 
249  // Return the joint angles to move to a given xyz location while
250  // pointing a certain direction
251  Eigen::VectorXd solveIK(
252  const Eigen::VectorXd& initial_positions,
253  const Eigen::Vector3d& target_xyz,
254  const Eigen::Vector3d& end_tip) const {
255  return kinematics_helper_.solveIK5Dof(*robot_model_, initial_positions, target_xyz, end_tip);
256  }
257 
258  // Return the joint angles to move to a given xyz location while
259  // pointing a certain direction
260  Eigen::VectorXd solveIK(
261  const Eigen::VectorXd& initial_positions,
262  const Eigen::Vector3d& target_xyz,
263  const Eigen::Matrix3d& orientation) const {
264  return kinematics_helper_.solveIK6Dof(*robot_model_, initial_positions, target_xyz, orientation);
265  }
266 
267 private:
268  // Private arm constructor
269  Arm(std::function<double()> get_current_time_s,
270  std::shared_ptr<Group> group,
271  std::shared_ptr<robot_model::RobotModel> robot_model,
272  std::shared_ptr<EndEffectorBase> end_effector = nullptr) :
273  get_current_time_s_(get_current_time_s),
274  last_time_(get_current_time_s()),
275  group_(group),
276  robot_model_(robot_model),
277  end_effector_(end_effector),
278  pos_(Eigen::VectorXd::Zero(group->size())),
279  vel_(Eigen::VectorXd::Zero(group->size())),
280  accel_(Eigen::VectorXd::Zero(group->size())),
281  feedback_(group->size()),
282  command_(group->size()) {}
283 
284  // Returns the aux state at this point in the trajectory
285  Eigen::VectorXd getAux(double t) const;
286 
287  std::function<double()> get_current_time_s_;
288  double last_time_;
289  std::shared_ptr<Group> group_;
290  std::shared_ptr<robot_model::RobotModel> robot_model_;
291  std::shared_ptr<EndEffectorBase> end_effector_;
292 
293  // The joint angle trajectory for reaching the current goal.
294  std::shared_ptr<trajectory::Trajectory> trajectory_;
295  double trajectory_start_time_{ std::numeric_limits<double>::quiet_NaN() };
296  // These are just temporary variables to cache output from
297  // Trajectory::getState.
298  Eigen::VectorXd pos_;
299  Eigen::VectorXd vel_;
300  Eigen::VectorXd accel_;
301 
302  // Local variable used to calculate grav comp efforts
303  Eigen::VectorXd masses_;
304 
305  // Along with a trajectory, aux states may be set. These are the last aux
306  // state for each timestep in the trajectory:
307  Eigen::VectorXd aux_times_;
308  Eigen::MatrixXd aux_;
309 
310  // Robot model helpers for FK + IK
312 
315 };
316 
317 } // namespace arm
318 } // namespace experimental
319 } // namespace hebi
A list of Feedback objects that can be received from a Group of modules; the size() must match the nu...
std::shared_ptr< robot_model::RobotModel > robot_model_
Definition: arm.hpp:290
Represents a group of physical HEBI modules, and allows Command, Feedback, and Info objects to be sen...
Definition: group.hpp:29
std::shared_ptr< robot_model::RobotModel > robot_model_
Definition: arm.hpp:63
double goalProgress() const
Definition: arm.cpp:211
Eigen::Vector3d FK(const Eigen::VectorXd &positions) const
Definition: arm.hpp:228
void FK5Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: arm.hpp:243
void clearJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:223
std::shared_ptr< trajectory::Trajectory > trajectory_
Definition: arm.hpp:294
Definition: arm.cpp:5
size_t size() const
Definition: arm.hpp:94
Represents a chain or tree of robot elements (rigid bodies and joints).
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
Definition: arm.hpp:260
std::function< double()> get_current_time_s_
Definition: arm.hpp:287
const EndEffectorBase * endEffector() const
Definition: arm.hpp:110
const Group & group() const
Definition: arm.hpp:97
const robot_model::RobotModel & robotModel() const
Definition: arm.hpp:100
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
Definition: arm.hpp:251
void setJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:217
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Definition: arm.hpp:238
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
Eigen::VectorXd vel_
Definition: arm.hpp:299
static std::unique_ptr< Arm > create(const Params &params)
Definition: arm.cpp:9
const GroupFeedback & lastFeedback() const
Definition: arm.hpp:120
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Definition: arm.hpp:233
std::shared_ptr< EndEffectorBase > end_effector_
Definition: arm.hpp:291
Eigen::VectorXd getAux(double t) const
Definition: arm.cpp:226
Eigen::MatrixXd aux_
Definition: arm.hpp:308
Eigen::VectorXd pos_
Definition: arm.hpp:298
Eigen::VectorXd solveIK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Eigen::Vector3d FK3Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions) const
bool atGoal() const
Definition: arm.hpp:205
Eigen::VectorXd accel_
Definition: arm.hpp:300
A list of Command objects appropriate for sending to a Group of modules; the size() must match the nu...
std::shared_ptr< Group > group_
Definition: arm.hpp:289
void FK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Eigen::VectorXd masses_
Definition: arm.hpp:303
Eigen::VectorXd solveIK6Dof(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Matrix3d &orientation) const
void setAuxState(const T &aux_state)
Definition: arm.hpp:180
std::function< double()> get_current_time_s_
Definition: arm.hpp:73
const GroupCommand & pendingCommand() const
Definition: arm.hpp:116
bool loadGains(const std::string &gains_file)
Definition: arm.cpp:66
Represents a smooth trajectory through a set of waypoints.
Definition: trajectory.hpp:19
GroupCommand & pendingCommand()
Definition: arm.hpp:115
void setGoal(const Goal &goal)
Definition: arm.cpp:147
const trajectory::Trajectory * trajectory() const
Definition: arm.hpp:105
std::vector< std::string > names_
Definition: arm.hpp:54
hebi::GroupFeedback feedback_
Definition: arm.hpp:313
std::vector< std::string > families_
Definition: arm.hpp:53
Arm(std::function< double()> get_current_time_s, std::shared_ptr< Group > group, std::shared_ptr< robot_model::RobotModel > robot_model, std::shared_ptr< EndEffectorBase > end_effector=nullptr)
Definition: arm.hpp:269
Eigen::VectorXd aux_times_
Definition: arm.hpp:307
hebi::GroupCommand command_
Definition: arm.hpp:314
void setJointLimits(const robot_model::RobotModel &robot_model, const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
std::shared_ptr< EndEffectorBase > end_effector_
Definition: arm.hpp:67
internal::KinematicsHelper kinematics_helper_
Definition: arm.hpp:311


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