19 namespace experimental {
49 std::string
name()
const {
return name_; }
73 virtual bool send() {
return true; }
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,
float value);
105 virtual bool applyParameter(
const std::string&
name,
const std::vector<float>& 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()};
179 Eigen::VectorXd i_error_{Eigen::VectorXd::Zero(6)};
185 bool gains_in_end_effector_frame_{};
189 Eigen::VectorXd kp_{Eigen::VectorXd::Zero(6)};
190 Eigen::VectorXd kd_{Eigen::VectorXd::Zero(6)};
191 Eigen::VectorXd ki_{Eigen::VectorXd::Zero(6)};
192 Eigen::VectorXd i_clamp_;
209 Eigen::VectorXd effort_offsets_{};
276 using clock = std::chrono::steady_clock;
277 static const clock::time_point start_time = clock::now();
278 return (std::chrono::duration<double>(clock::now() - start_time)).count();
287 static std::unique_ptr<Arm>
create(
const Params& params);
290 bool addPlugin(std::unique_ptr<plugin::Plugin> plugin);
296 for (
auto& p : plugins_) {
297 if (dynamic_cast<T*>(p.get()) !=
nullptr)
303 std::weak_ptr<plugin::Plugin>
getPluginByName(
const std::string& name);
308 bool loadGains(
const std::string& gains_file);
315 size_t size()
const {
return group_->size(); }
406 auto aux_size = aux_state.size();
407 if (aux_state.size() > 0) {
408 aux_times_.resize(1);
409 aux_times_[0] = get_current_time_s_();
410 aux_.resize(aux_size, 1);
412 for (
size_t i = 0; i < aux_size; i++) {
413 aux_(i, 0) = aux_state[i];
418 aux_times_.resize(0);
442 void setJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
443 kinematics_helper_.
setJointLimits(*robot_model_, min_positions, max_positions);
448 void clearJointLimits(
const Eigen::VectorXd& min_positions,
const Eigen::VectorXd& max_positions) {
453 Eigen::Vector3d
FK(
const Eigen::VectorXd& positions)
const {
454 return kinematics_helper_.
FK3Dof(*robot_model_, positions);
458 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Vector3d& tip_axis)
const {
459 kinematics_helper_.
FK5Dof(*robot_model_, positions, xyz_out, tip_axis);
463 void FK(
const Eigen::VectorXd& positions, Eigen::Vector3d& xyz_out, Eigen::Matrix3d& orientation)
const {
464 kinematics_helper_.
FK6Dof(*robot_model_, positions, xyz_out, orientation);
468 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz)
const {
469 return kinematics_helper_.
solveIK3Dof(*robot_model_, initial_positions, target_xyz);
474 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz,
475 const Eigen::Vector3d& end_tip)
const {
476 return kinematics_helper_.
solveIK5Dof(*robot_model_, initial_positions, target_xyz, end_tip);
481 Eigen::VectorXd
solveIK(
const Eigen::VectorXd& initial_positions,
const Eigen::Vector3d& target_xyz,
482 const Eigen::Matrix3d& orientation)
const {
483 return kinematics_helper_.
solveIK6Dof(*robot_model_, initial_positions, target_xyz, orientation);
488 Arm(std::function<
double()> get_current_time_s, std::shared_ptr<Group>
group,
489 std::shared_ptr<robot_model::RobotModel> robot_model, std::shared_ptr<EndEffectorBase> end_effector =
nullptr)
490 : get_current_time_s_(get_current_time_s),
491 last_time_(get_current_time_s()),
492 group_(std::move(
group)),
493 robot_model_(std::move(robot_model)),
494 end_effector_(std::move(end_effector)),
495 pos_(Eigen::VectorXd::Zero(group_->
size())),
496 vel_(Eigen::VectorXd::Zero(group_->
size())),
497 accel_(Eigen::VectorXd::Zero(group_->
size())),
498 feedback_(group_->
size()),
499 command_(group_->
size()) {}
502 Eigen::VectorXd getAux(
double t)
const;
504 std::function<double()> get_current_time_s_;
506 std::shared_ptr<Group> group_;
507 std::shared_ptr<robot_model::RobotModel> robot_model_;
508 std::shared_ptr<EndEffectorBase> end_effector_;
511 std::shared_ptr<trajectory::Trajectory> trajectory_;
512 double trajectory_start_time_{std::numeric_limits<double>::quiet_NaN()};
515 Eigen::VectorXd pos_;
516 Eigen::VectorXd vel_;
517 Eigen::VectorXd accel_;
521 Eigen::VectorXd aux_times_;
522 Eigen::MatrixXd aux_;
525 internal::KinematicsHelper kinematics_helper_;
531 std::vector<std::shared_ptr<plugin::Plugin>> plugins_;
virtual bool send()
Definition: arm.hpp:73
size_t size() const
Definition: arm.hpp:315
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:330
Represents a group of physical HEBI modules, and allows Command, Feedback, and Info objects to be sen...
Definition: group.hpp:35
std::shared_ptr< robot_model::RobotModel > robot_model_
Definition: arm.hpp:265
Plugin(const std::string &name)
Definition: arm.hpp:45
const robot_model::RobotModel & robotModel() const
Definition: arm.hpp:321
void cancelGoal()
Definition: arm.cpp:626
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
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:221
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:481
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:319
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:101
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 clearJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:448
virtual ~Plugin()=default
bool applyParameterImpl(const std::string &name, const std::vector< float > &value) override
Definition: arm.cpp:308
static std::string pluginTypeName()
Definition: arm.hpp:198
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz, const Eigen::Vector3d &end_tip) const
Definition: arm.hpp:474
virtual bool applyParameterImpl(const std::string &name, const std::string &value)
Definition: arm.hpp:93
bool enabled() const
Definition: arm.hpp:55
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Vector3d &tip_axis) const
Definition: arm.hpp:458
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:261
bool setRampTime(float ramp_time)
Definition: arm.cpp:14
const GroupFeedback & lastFeedback() const
Definition: arm.hpp:345
bool send()
Definition: arm.cpp:535
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:456
virtual bool applyParameterImpl(const std::string &name, const std::vector< float > &value)
Definition: arm.hpp:92
std::string hrdf_file_
Definition: arm.hpp:264
bool atGoal() const
Definition: arm.hpp:430
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:214
virtual bool applyParameterImpl(const std::string &name, const std::vector< std::string > &value)
Definition: arm.hpp:94
static std::unique_ptr< ImpedanceController > create(const PluginConfig &)
Definition: arm.cpp:181
void setJointLimits(const Eigen::VectorXd &min_positions, const Eigen::VectorXd &max_positions)
Definition: arm.hpp:442
const Group & group() const
Definition: arm.hpp:318
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:301
bool applyParameterImpl(const std::string &name, float value) override
Definition: arm.cpp:118
static std::string pluginTypeName()
Definition: arm.hpp:163
bool applyParameters(const PluginConfig &config, std::set< std::string > required_parameters)
Definition: arm.cpp:21
const EndEffectorBase * endEffector() const
Definition: arm.hpp:335
static std::unique_ptr< EffortOffset > create(const PluginConfig &)
Definition: arm.cpp:294
void FK(const Eigen::VectorXd &positions, Eigen::Vector3d &xyz_out, Eigen::Matrix3d &orientation) const
Definition: arm.hpp:463
int command_lifetime_
Definition: arm.hpp:258
void setEnabled(bool enabled)
Definition: arm.hpp:58
const GroupCommand & pendingCommand() const
Definition: arm.hpp:341
double goalProgress() const
Definition: arm.cpp:616
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
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:108
bool update(Arm &, double dt)
Definition: arm.cpp:86
std::weak_ptr< plugin::Plugin > getPluginByType()
Definition: arm.hpp:295
float enabledRatio()
Definition: arm.hpp:61
bool onAssociated(const Arm &arm) override
Definition: arm.cpp:188
virtual bool applyParameterImpl(const std::string &name, float value)
Definition: arm.hpp:91
void setAuxState(const T &aux_state)
Definition: arm.hpp:405
std::function< double()> get_current_time_s_
Definition: arm.hpp:275
Definition: plugin_config.hpp:12
Definition: end_effector.hpp:12
bool loadGains(const std::string &gains_file)
Definition: arm.cpp:477
Eigen::VectorXd solveIK(const Eigen::VectorXd &initial_positions, const Eigen::Vector3d &target_xyz) const
Definition: arm.hpp:468
Represents a smooth trajectory through a set of waypoints.
Definition: trajectory.hpp:19
robot_model::RobotModel & robotModel()
Definition: arm.hpp:325
static std::unique_ptr< Arm > create(const RobotConfig &config)
Definition: arm.cpp:326
std::weak_ptr< plugin::Plugin > getPluginByName(const std::string &name)
Definition: arm.cpp:469
GroupCommand & pendingCommand()
Definition: arm.hpp:340
Definition: robot_config.hpp:13
void setGoal(const Goal &goal)
Definition: arm.cpp:552
Eigen::Vector3d FK(const Eigen::VectorXd &positions) const
Definition: arm.hpp:453
std::vector< std::string > names_
Definition: arm.hpp:256
virtual bool applyParameterImpl(const std::string &name, const std::vector< bool > &value)
Definition: arm.hpp:90
bool applyParameterImpl(const std::string &name, bool value) override
Definition: arm.cpp:192
virtual bool updateImpl(Arm &, double dt)=0
std::vector< std::string > families_
Definition: arm.hpp:255
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
virtual bool applyParameterImpl(const std::string &name, bool value)
Definition: arm.hpp:89
bool updateImpl(Arm &arm, double dt) override
Definition: arm.cpp:155
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:269
bool update()
Definition: arm.cpp:485