21 namespace experimental {
54 std::string
name()
const {
return name_; }
78 virtual bool send() {
return true; }
95 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<bool>& ) {
return false; }
97 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<double>& ) {
return false; }
99 virtual bool applyParameterImpl(
const std::string& ,
const std::vector<std::string>& ) {
return false; }
105 virtual bool applyParameter(
const std::string&
name,
bool value);
106 virtual bool applyParameter(
const std::string&
name,
const std::vector<bool>& value) {
109 virtual bool applyParameter(
const std::string&
name,
double value);
110 virtual bool applyParameter(
const std::string&
name,
const std::vector<double>& value) {
113 virtual bool applyParameter(
const std::string&
name,
const std::string& value) {
116 virtual bool applyParameter(
const std::string&
name,
const std::vector<std::string>& value) {
121 const std::string name_{};
127 double enabled_ratio_{1.};
158 Eigen::VectorXd grav_efforts_;
160 size_t imu_feedback_index_{};
161 size_t imu_frame_index_{};
162 Eigen::Matrix3d imu_local_transform_{Eigen::Matrix3d::Identity()};
177 Eigen::VectorXd dyn_efforts_;
191 bool setKp(
const Eigen::VectorXd&
kp);
193 Eigen::VectorXd
kp()
const {
return kp_; }
196 bool setKd(
const Eigen::VectorXd&
kd);
198 Eigen::VectorXd
kd()
const {
return kd_; }
201 bool setKi(
const Eigen::VectorXd&
ki);
203 Eigen::VectorXd
ki()
const {
return ki_; }
206 bool setIClamp(
const Eigen::VectorXd& i_clamp);
208 Eigen::VectorXd
iClamp()
const {
return i_clamp_; }
212 bool setParam(
const std::string&
name,
const Eigen::VectorXd& value_vector);
225 Eigen::VectorXd i_error_{Eigen::VectorXd::Zero(6)};
231 bool gains_in_end_effector_frame_{};
235 Eigen::VectorXd kp_{Eigen::VectorXd::Zero(6)};
236 Eigen::VectorXd kd_{Eigen::VectorXd::Zero(6)};
237 Eigen::VectorXd ki_{Eigen::VectorXd::Zero(6)};
238 Eigen::VectorXd i_clamp_;
255 Eigen::VectorXd effort_offsets_{};
276 std::shared_ptr<hebi::Group> group_;
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();
361 static std::unique_ptr<Arm>
create(
const Params& params);
364 static std::unique_ptr<Arm>
create(
const Params& config,
const Lookup& lookup);
367 bool addPlugin(std::unique_ptr<plugin::Plugin> plugin);
373 for (
auto& p : plugins_) {
374 if (dynamic_cast<T*>(p.get()) !=
nullptr)
380 std::weak_ptr<plugin::Plugin>
getPluginByName(
const std::string& name);
385 bool loadGains(
const std::string& gains_file);
398 size_t size()
const {
return group_->size(); }
501 void currentState(Eigen::VectorXd& positions, Eigen::VectorXd& velocities, Eigen::VectorXd& accelerations)
const;
507 auto aux_size = aux_state.size();
508 if (aux_state.size() > 0) {
509 aux_times_.resize(1);
510 aux_times_[0] = get_current_time_s_();
511 aux_.resize(aux_size, 1);
513 for (
size_t i = 0; i < aux_size; i++) {
514 aux_(i, 0) = aux_state[i];
519 aux_times_.resize(0);
543 void setJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
544 kinematics_helper_.
setJointLimits(*robot_model_, min_positions, max_positions);
554 Eigen::Vector3d
FK(
const Eigen::VectorXd& positions)
const {
555 return kinematics_helper_.
FK3Dof(*robot_model_, positions);
559 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Vector3d& tip_axis)
const {
560 kinematics_helper_.
FK5Dof(*robot_model_, positions, xyz_out, tip_axis);
564 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Matrix3d& orientation)
const {
565 kinematics_helper_.
FK6Dof(*robot_model_, positions, xyz_out, orientation);
569 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz)
const {
570 return kinematics_helper_.
solveIK3Dof(*robot_model_, initial_positions, target_xyz);
575 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz,
576 const Eigen::Vector3d& end_tip)
const {
577 return kinematics_helper_.
solveIK5Dof(*robot_model_, initial_positions, target_xyz, end_tip);
582 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz,
583 const Eigen::Matrix3d& orientation)
const {
584 return kinematics_helper_.
solveIK6Dof(*robot_model_, initial_positions, target_xyz, orientation);
589 Arm(std::function<
double()> get_current_time_s, std::shared_ptr<Group>
group,
590 std::shared_ptr<robot_model::RobotModel> robot_model, std::shared_ptr<EndEffectorBase> end_effector =
nullptr)
591 : get_current_time_s_(get_current_time_s),
592 last_time_(get_current_time_s()),
593 group_(std::move(
group)),
594 robot_model_(std::move(robot_model)),
595 end_effector_(std::move(end_effector)),
596 pos_(Eigen::VectorXd::Zero(group_->
size())),
597 vel_(Eigen::VectorXd::Zero(group_->
size())),
598 accel_(Eigen::VectorXd::Zero(group_->
size())),
599 feedback_(group_->
size()),
600 command_(group_->
size()) {}
605 static std::unique_ptr<Arm>
create(
const Params& config,
const Lookup* lookup);
608 Eigen::VectorXd getAux(
double t)
const;
610 std::function<double()> get_current_time_s_;
612 std::shared_ptr<Group> group_;
613 std::shared_ptr<robot_model::RobotModel> robot_model_;
614 std::shared_ptr<EndEffectorBase> end_effector_;
617 std::shared_ptr<trajectory::Trajectory> trajectory_;
618 double trajectory_start_time_{std::numeric_limits<double>::quiet_NaN()};
621 Eigen::VectorXd pos_;
622 Eigen::VectorXd vel_;
623 Eigen::VectorXd accel_;
627 Eigen::VectorXd aux_times_;
628 Eigen::MatrixXd aux_;
631 internal::KinematicsHelper kinematics_helper_;
637 std::vector<std::shared_ptr<plugin::Plugin>> plugins_;
639 friend plugin::DynamicsCompensationEffort;
void setJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:543
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:531
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:436
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:428
bool setKi(const Eigen::VectorXd &ki)
Definition: arm.cpp:229
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
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:582
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
bool applyParameterImpl(const std::string &name, double value) override
Definition: arm.cpp:120
void setAuxState(const T &aux_state)
Definition: arm.hpp:506
bool gainsInEndEffectorFrame() const
Definition: arm.hpp:188
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:554
Plugin for providing gravity compensating torques for the arm.
Definition: arm.hpp:142
void clearJointLimits()
Definition: arm.hpp:549
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:417
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: arm.hpp:569
bool setKp(const Eigen::VectorXd &kp)
Definition: arm.cpp:221
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
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:564
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:422
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:432
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
const GroupFeedback & lastFeedback() const
Definition: arm.hpp:440
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:575
Definition: end_effector.hpp:11
virtual bool applyParameterImpl(const std::string &, const std::string &)
Definition: arm.hpp:98
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
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:190
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:559
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