19 namespace experimental {
49 std::string
name()
const {
return name_; }
73 virtual bool send() {
return true; }
90 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<bool>& ) {
return false; }
92 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<double>& ) {
return false; }
94 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<std::string>& ) {
return false; }
100 virtual bool applyParameter(
const std::string&
name,
bool value);
101 virtual bool applyParameter(
const std::string&
name,
const std::vector<bool>& value) {
104 virtual bool applyParameter(
const std::string&
name,
double value);
105 virtual bool applyParameter(
const std::string&
name,
const std::vector<double>& value) {
108 virtual bool applyParameter(
const std::string&
name,
const std::string& value) {
111 virtual bool applyParameter(
const std::string&
name,
const std::vector<std::string>& value) {
116 const std::string name_{};
122 float enabled_ratio_{1.f};
153 Eigen::VectorXd grav_efforts_;
155 size_t imu_feedback_index_{};
156 size_t imu_frame_index_{};
157 Eigen::Matrix3d imu_local_transform_{Eigen::Matrix3d::Identity()};
172 Eigen::VectorXd dyn_efforts_;
186 bool setKp(
const Eigen::VectorXd&
kp);
188 Eigen::VectorXd
kp()
const {
return kp_; }
191 bool setKd(
const Eigen::VectorXd&
kd);
193 Eigen::VectorXd
kd()
const {
return kd_; }
196 bool setKi(
const Eigen::VectorXd&
ki);
198 Eigen::VectorXd
ki()
const {
return ki_; }
201 bool setIClamp(
const Eigen::VectorXd& i_clamp);
203 Eigen::VectorXd
iClamp()
const {
return i_clamp_; }
207 bool setParam(
const std::string&
name,
const Eigen::VectorXd& value_vector);
220 Eigen::VectorXd i_error_{Eigen::VectorXd::Zero(6)};
226 bool gains_in_end_effector_frame_{};
230 Eigen::VectorXd kp_{Eigen::VectorXd::Zero(6)};
231 Eigen::VectorXd kd_{Eigen::VectorXd::Zero(6)};
232 Eigen::VectorXd ki_{Eigen::VectorXd::Zero(6)};
233 Eigen::VectorXd i_clamp_;
250 Eigen::VectorXd effort_offsets_{};
271 std::shared_ptr<hebi::Group> group_;
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();
355 static std::unique_ptr<Arm>
create(
const Params& params);
358 static std::unique_ptr<Arm>
create(
const Params& config,
const Lookup& lookup);
361 bool addPlugin(std::unique_ptr<plugin::Plugin> plugin);
367 for (
auto& p : plugins_) {
368 if (dynamic_cast<T*>(p.get()) !=
nullptr)
374 std::weak_ptr<plugin::Plugin>
getPluginByName(
const std::string& name);
379 bool loadGains(
const std::string& gains_file);
386 size_t size()
const {
return group_->size(); }
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);
483 for (
size_t i = 0; i < aux_size; i++) {
484 aux_(i, 0) = aux_state[i];
489 aux_times_.resize(0);
513 void setJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
514 kinematics_helper_.
setJointLimits(*robot_model_, min_positions, max_positions);
524 Eigen::Vector3d
FK(
const Eigen::VectorXd& positions)
const {
525 return kinematics_helper_.
FK3Dof(*robot_model_, positions);
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);
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);
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);
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);
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);
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()) {}
575 static std::unique_ptr<Arm>
create(
const Params& config,
const Lookup* lookup);
578 Eigen::VectorXd getAux(
double t)
const;
580 std::function<double()> get_current_time_s_;
582 std::shared_ptr<Group> group_;
583 std::shared_ptr<robot_model::RobotModel> robot_model_;
584 std::shared_ptr<EndEffectorBase> end_effector_;
587 std::shared_ptr<trajectory::Trajectory> trajectory_;
588 double trajectory_start_time_{std::numeric_limits<double>::quiet_NaN()};
591 Eigen::VectorXd pos_;
592 Eigen::VectorXd vel_;
593 Eigen::VectorXd accel_;
597 Eigen::VectorXd aux_times_;
598 Eigen::MatrixXd aux_;
601 internal::KinematicsHelper kinematics_helper_;
607 std::vector<std::shared_ptr<plugin::Plugin>> plugins_;
609 friend plugin::DynamicsCompensationEffort;
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
virtual ~Plugin()=default
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
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
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
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