24 struct MultiBodyConfig;
40 const Eigen::VectorXd & dimWeight,
43 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
45 void dimWeight(
const Eigen::VectorXd & dim);
47 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
49 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
51 virtual const Eigen::MatrixXd & Q()
const override;
52 virtual const Eigen::VectorXd & C()
const override;
55 void computeQC(Eigen::VectorXd & error);
62 Eigen::VectorXd dimWeight_;
63 int robotIndex_, alphaDBegin_;
68 Eigen::MatrixXd preQ_;
69 Eigen::VectorXd preC_;
85 const Eigen::VectorXd & dimWeight,
90 void stiffness(
double stiffness);
92 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
93 const std::vector<rbd::MultiBodyConfig> & mbcs,
97 double stiffness_, stiffnessSqrt_;
115 const Eigen::VectorXd & dimWeight,
118 void setGains(
double gainPos,
double gainVel);
120 void errorPos(
const Eigen::VectorXd & errorPos);
121 void errorVel(
const Eigen::VectorXd & errorVel);
122 void refAccel(
const Eigen::VectorXd & refAccel);
124 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
125 const std::vector<rbd::MultiBodyConfig> & mbcs,
129 double gainPos_, gainVel_;
130 Eigen::VectorXd errorPos_, errorVel_, refAccel_;
148 const Eigen::VectorXd & dimWeight,
151 void setGains(
double gainPos,
double gainVel);
152 void setGains(
const Eigen::VectorXd & stiffness,
const Eigen::VectorXd & damping);
153 void stiffness(
double gainPos);
154 void stiffness(
const Eigen::VectorXd & stiffness);
155 const Eigen::VectorXd & stiffness()
const;
156 void damping(
double gainVel);
157 void damping(
const Eigen::VectorXd & damping);
158 const Eigen::VectorXd & damping()
const;
160 void refVel(
const Eigen::VectorXd & refVel);
161 const Eigen::VectorXd & refVel()
const;
162 void refAccel(
const Eigen::VectorXd & refAccel);
163 const Eigen::VectorXd & refAccel()
const;
165 void update(
const std::vector<rbd::MultiBody> & mbs,
166 const std::vector<rbd::MultiBodyConfig> & mbcs,
170 Eigen::VectorXd stiffness_, damping_;
171 Eigen::VectorXd refVel_, refAccel_;
178 PIDTask(
const std::vector<rbd::MultiBody> & mbs,
186 PIDTask(
const std::vector<rbd::MultiBody> & mbs,
192 const Eigen::VectorXd & dimWeight,
202 void error(
const Eigen::VectorXd & err);
203 void errorD(
const Eigen::VectorXd & errD);
204 void errorI(
const Eigen::VectorXd & errI);
206 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
207 const std::vector<rbd::MultiBodyConfig> & mbcs,
212 Eigen::VectorXd error_, errorD_, errorI_;
223 const Eigen::VectorXd & objDot,
231 const Eigen::VectorXd & objDot,
232 const Eigen::VectorXd & dimWeight,
235 double duration()
const;
236 void duration(
double d);
238 int iter()
const {
return iter_; }
239 void iter(
int i) { iter_ = i; }
244 const Eigen::VectorXd &
objDot()
const {
return objDot_; }
245 void objDot(
const Eigen::VectorXd & o) { objDot_ = o; }
247 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
248 void dimWeight(
const Eigen::VectorXd & o) { dimWeight_ = o; }
250 const Eigen::VectorXd &
phi()
const {
return phi_; }
251 const Eigen::VectorXd &
psi()
const {
return psi_; }
253 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
255 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
256 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
257 const std::vector<rbd::MultiBodyConfig> & mbcs,
260 virtual const Eigen::MatrixXd & Q()
const override;
261 virtual const Eigen::VectorXd & C()
const override;
268 Eigen::VectorXd objDot_;
269 Eigen::VectorXd dimWeight_;
270 int robotIndex_, alphaDBegin_;
272 Eigen::VectorXd phi_, psi_;
277 Eigen::MatrixXd preQ_;
278 Eigen::VectorXd CVecSum_, preC_;
284 static JointsSelector ActiveJoints(
const std::vector<rbd::MultiBody> & mbs,
287 const std::vector<std::string> & activeJointsName,
288 const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
289 static JointsSelector UnactiveJoints(
const std::vector<rbd::MultiBody> & mbs,
292 const std::vector<std::string> & unactiveJointsName,
293 const std::map<std::string, std::vector<std::array<int, 2>>> & unactiveDofs = {});
305 const std::vector<std::string> & selectedJointsName,
306 const std::map<std::string, std::vector<std::array<int, 2>>> & activeDofs = {});
308 const std::vector<SelectedData>
selectedJoints()
const {
return selectedJoints_; }
310 virtual int dim()
override;
311 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
312 const std::vector<rbd::MultiBodyConfig> & mbcs,
315 virtual const Eigen::MatrixXd & jac()
const override;
316 virtual const Eigen::VectorXd & eval()
const override;
317 virtual const Eigen::VectorXd & speed()
const override;
318 virtual const Eigen::VectorXd & normalAcc()
const override;
321 Eigen::MatrixXd jac_;
322 std::vector<SelectedData> selectedJoints_;
340 damping = 2. * std::sqrt(stif);
352 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
int robotIndex,
const TorqueBound & tb,
double weight);
354 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
357 const Eigen::VectorXd & jointSelect,
360 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
363 const std::string & efName,
366 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
373 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
378 const Eigen::VectorXd & jointSelect,
381 TorqueTask(
const std::vector<rbd::MultiBody> & mbs,
386 const std::string & efName,
389 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
390 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
391 const std::vector<rbd::MultiBodyConfig> & mbcs,
394 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(0, 0); }
396 virtual const Eigen::MatrixXd &
Q()
const override {
return Q_; }
398 virtual const Eigen::VectorXd &
C()
const override {
return C_; }
400 virtual const Eigen::VectorXd &
jointSelect()
const {
return jointSelector_; }
404 int alphaDBegin_, lambdaBegin_;
406 Eigen::VectorXd jointSelector_;
414 PostureTask(
const std::vector<rbd::MultiBody> & mbs,
416 std::vector<std::vector<double>> q,
422 void posture(std::vector<std::vector<double>> q) { pt_.posture(q); }
424 const std::vector<std::vector<double>>
posture()
const {
return pt_.posture(); }
430 void stiffness(
double stiffness);
432 void gains(
double stiffness);
433 void gains(
double stiffness,
double damping);
435 void jointsStiffness(
const std::vector<rbd::MultiBody> & mbs,
const std::vector<JointStiffness> & jsv);
437 void jointsGains(
const std::vector<rbd::MultiBody> & mbs,
const std::vector<JointGains> & jgv);
439 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(alphaDBegin_, alphaDBegin_); }
441 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
442 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
443 const std::vector<rbd::MultiBodyConfig> & mbcs,
446 virtual const Eigen::MatrixXd & Q()
const override;
447 virtual const Eigen::VectorXd & C()
const override;
449 const Eigen::VectorXd & eval()
const;
451 inline void refVel(
const Eigen::VectorXd & refVel) noexcept { refVel_ =
refVel; }
452 inline const Eigen::VectorXd &
refVel() const noexcept {
return refVel_; }
453 inline void refAccel(
const Eigen::VectorXd & refAccel) noexcept
455 assert(refAccel.size() == refAccel_.size());
456 refAccel_ = refAccel;
458 inline const Eigen::VectorXd &
refAccel() const noexcept {
return refAccel_; }
460 inline const Eigen::VectorXd &
dimWeight() const noexcept {
return dimWeight_; }
462 inline void dimWeight(
const Eigen::VectorXd & dimW) noexcept
464 assert(dimW.size() == dimWeight_.size());
471 double stiffness, damping;
480 int robotIndex_, alphaDBegin_;
482 std::vector<JointData> jointDatas_;
486 Eigen::VectorXd alphaVec_;
487 Eigen::VectorXd refVel_, refAccel_;
488 Eigen::VectorXd dimWeight_;
496 const std::string & bodyName,
497 const Eigen::Vector3d & pos,
498 const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
502 void position(
const Eigen::Vector3d & pos) { pt_.position(pos); }
504 const Eigen::Vector3d &
position()
const {
return pt_.position(); }
506 void bodyPoint(
const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
508 const Eigen::Vector3d &
bodyPoint()
const {
return pt_.bodyPoint(); }
510 virtual int dim()
override;
511 virtual void update(
const std::vector<rbd::MultiBody> & mb,
512 const std::vector<rbd::MultiBodyConfig> & mbc,
515 virtual const Eigen::MatrixXd & jac()
const override;
516 virtual const Eigen::VectorXd & eval()
const override;
517 virtual const Eigen::VectorXd & speed()
const override;
518 virtual const Eigen::VectorXd & normalAcc()
const override;
530 const std::string & bodyName,
531 const Eigen::Quaterniond & ori);
534 const std::string & bodyName,
535 const Eigen::Matrix3d & ori);
539 void orientation(
const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
541 void orientation(
const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
543 const Eigen::Matrix3d &
orientation()
const {
return ot_.orientation(); }
545 virtual int dim()
override;
546 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
547 const std::vector<rbd::MultiBodyConfig> & mbcs,
550 virtual const Eigen::MatrixXd & jac()
const override;
551 virtual const Eigen::VectorXd & eval()
const override;
552 virtual const Eigen::VectorXd & speed()
const override;
553 virtual const Eigen::VectorXd & normalAcc()
const override;
560 template<
typename transform_task_t>
566 const std::string & bodyName,
567 const sva::PTransformd & X_0_t,
568 const sva::PTransformd &
X_b_p = sva::PTransformd::Identity())
575 void target(
const sva::PTransformd & X_0_t) {
tt_.target(X_0_t); }
577 const sva::PTransformd &
target()
const {
return tt_.target(); }
581 const sva::PTransformd &
X_b_p()
const {
return tt_.X_b_p(); }
583 virtual int dim()
override {
return 6; }
585 virtual const Eigen::MatrixXd &
jac()
const override {
return tt_.jac(); }
587 virtual const Eigen::VectorXd &
eval()
const override {
return tt_.eval(); }
589 virtual const Eigen::VectorXd &
speed()
const override {
return tt_.speed(); }
591 virtual const Eigen::VectorXd &
normalAcc()
const override {
return tt_.normalAcc(); }
604 const std::string & bodyName,
605 const sva::PTransformd & X_0_t,
606 const sva::PTransformd & X_b_p = sva::PTransformd::Identity());
608 virtual void update(
const std::vector<rbd::MultiBody> & mb,
609 const std::vector<rbd::MultiBodyConfig> & mbc,
619 const std::string & bodyName,
620 const sva::PTransformd & X_0_t,
621 const sva::PTransformd & X_b_p = sva::PTransformd::Identity(),
622 const Eigen::Matrix3d & E_0_c = Eigen::Matrix3d::Identity());
624 void E_0_c(
const Eigen::Matrix3d & E_0_c);
625 const Eigen::Matrix3d & E_0_c()
const;
627 virtual void update(
const std::vector<rbd::MultiBody> & mb,
628 const std::vector<rbd::MultiBodyConfig> & mbc,
637 const std::string & bodyName,
638 const Eigen::Quaterniond & ori,
639 const sva::PTransformd & X_b_s);
642 const std::string & bodyName,
643 const Eigen::Matrix3d & ori,
644 const sva::PTransformd & X_b_s);
648 void orientation(
const Eigen::Quaterniond & ori) { ot_.orientation(ori); }
650 void orientation(
const Eigen::Matrix3d & ori) { ot_.orientation(ori); }
652 const Eigen::Matrix3d &
orientation()
const {
return ot_.orientation(); }
654 virtual int dim()
override;
655 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
656 const std::vector<rbd::MultiBodyConfig> & mbcs,
659 virtual const Eigen::MatrixXd & jac()
const override;
660 virtual const Eigen::VectorXd & eval()
const override;
661 virtual const Eigen::VectorXd & speed()
const override;
662 virtual const Eigen::VectorXd & normalAcc()
const override;
672 GazeTask(
const std::vector<rbd::MultiBody> & mbs,
674 const std::string & bodyName,
675 const Eigen::Vector2d & point2d,
676 double depthEstimate,
677 const sva::PTransformd & X_b_gaze,
678 const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
679 GazeTask(
const std::vector<rbd::MultiBody> & mbs,
681 const std::string & bodyName,
682 const Eigen::Vector3d & point3d,
683 const sva::PTransformd & X_b_gaze,
684 const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
688 void error(
const Eigen::Vector2d & point2d,
const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
690 gazet_.error(point2d, point2d_ref);
693 void error(
const Eigen::Vector3d & point3d,
const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero())
695 gazet_.error(point3d, point2d_ref);
698 virtual int dim()
override;
699 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
700 const std::vector<rbd::MultiBodyConfig> & mbcs,
703 virtual const Eigen::MatrixXd & jac()
const override;
704 virtual const Eigen::VectorXd & eval()
const override;
705 virtual const Eigen::VectorXd & speed()
const override;
706 virtual const Eigen::VectorXd & normalAcc()
const override;
718 const std::string & bodyName,
719 const sva::PTransformd & X_t_s,
720 const sva::PTransformd & X_b_s = sva::PTransformd::Identity());
724 void error(
const sva::PTransformd & X_t_s) { pbvst_.error(X_t_s); }
726 virtual int dim()
override;
727 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
728 const std::vector<rbd::MultiBodyConfig> & mbcs,
731 virtual const Eigen::MatrixXd & jac()
const override;
732 virtual const Eigen::VectorXd & eval()
const override;
733 virtual const Eigen::VectorXd & speed()
const override;
734 virtual const Eigen::VectorXd & normalAcc()
const override;
744 CoMTask(
const std::vector<rbd::MultiBody> & mbs,
int robotIndex,
const Eigen::Vector3d & com);
745 CoMTask(
const std::vector<rbd::MultiBody> & mbs,
747 const Eigen::Vector3d & com,
748 std::vector<double> weight);
752 void com(
const Eigen::Vector3d & com) { ct_.com(com); }
754 const Eigen::Vector3d &
com()
const {
return ct_.com(); }
756 const Eigen::Vector3d &
actual()
const {
return ct_.actual(); }
758 void updateInertialParameters(
const std::vector<rbd::MultiBody> & mbs);
760 virtual int dim()
override;
761 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
762 const std::vector<rbd::MultiBodyConfig> & mbcs,
765 virtual const Eigen::MatrixXd & jac()
const override;
766 virtual const Eigen::VectorXd & eval()
const override;
767 virtual const Eigen::VectorXd & speed()
const override;
768 virtual const Eigen::VectorXd & normalAcc()
const override;
779 std::vector<int> robotIndexes,
780 const Eigen::Vector3d & com,
784 std::vector<int> robotIndexes,
785 const Eigen::Vector3d & com,
787 const Eigen::Vector3d & dimWeight,
792 void com(
const Eigen::Vector3d & com) { mct_.com(com); }
794 const Eigen::Vector3d
com()
const {
return mct_.com(); }
796 void updateInertialParameters(
const std::vector<rbd::MultiBody> & mbs);
800 void stiffness(
double stiffness);
802 void dimWeight(
const Eigen::Vector3d & dim);
804 const Eigen::Vector3d &
dimWeight()
const {
return dimWeight_; }
806 virtual std::pair<int, int>
begin()
const override {
return {alphaDBegin_, alphaDBegin_}; }
808 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
809 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
810 const std::vector<rbd::MultiBodyConfig> & mbcs,
813 virtual const Eigen::MatrixXd & Q()
const override;
814 virtual const Eigen::VectorXd & C()
const override;
816 const Eigen::VectorXd & eval()
const;
817 const Eigen::VectorXd & speed()
const;
820 void init(
const std::vector<rbd::MultiBody> & mbs);
824 double stiffness_, stiffnessSqrt_;
825 Eigen::Vector3d dimWeight_;
826 std::vector<int> posInQ_;
830 Eigen::Vector3d CSum_;
832 Eigen::MatrixXd preQ_;
841 const std::string & r1BodyName,
842 const std::string & r2BodyName,
843 const sva::PTransformd & X_r1b_r1s,
844 const sva::PTransformd & X_r2b_r2s,
850 void X_r1b_r1s(
const sva::PTransformd & X_r1b_r1s);
851 const sva::PTransformd & X_r1b_r1s()
const;
853 void X_r2b_r2s(
const sva::PTransformd & X_r2b_r2s);
854 const sva::PTransformd & X_r2b_r2s()
const;
858 void stiffness(
double stiffness);
860 void dimWeight(
const Eigen::Vector6d & dim);
862 const Eigen::VectorXd &
dimWeight()
const {
return dimWeight_; }
864 virtual std::pair<int, int>
begin()
const override {
return {alphaDBegin_, alphaDBegin_}; }
866 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
867 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
868 const std::vector<rbd::MultiBodyConfig> & mbcs,
871 virtual const Eigen::MatrixXd & Q()
const override;
872 virtual const Eigen::VectorXd & C()
const override;
874 const Eigen::VectorXd & eval()
const;
875 const Eigen::VectorXd & speed()
const;
879 double stiffness_, stiffnessSqrt_;
880 Eigen::VectorXd dimWeight_;
881 std::vector<int> posInQ_, robotIndexes_;
885 Eigen::VectorXd CSum_;
887 Eigen::MatrixXd preQ_;
893 MomentumTask(
const std::vector<rbd::MultiBody> & mbs,
int robotIndex,
const sva::ForceVecd & mom);
897 void momentum(
const sva::ForceVecd & mom) { momt_.momentum(mom); }
899 const sva::ForceVecd
momentum()
const {
return momt_.momentum(); }
901 virtual int dim()
override;
902 virtual void update(
const std::vector<rbd::MultiBody> & mb,
903 const std::vector<rbd::MultiBodyConfig> & mbc,
906 virtual const Eigen::MatrixXd & jac()
const override;
907 virtual const Eigen::VectorXd & eval()
const override;
908 virtual const Eigen::VectorXd & speed()
const override;
909 virtual const Eigen::VectorXd & normalAcc()
const override;
920 :
Task(weight), contactId_(contactId), begin_(0), stiffness_(stiffness), stiffnessSqrt_(2 * std::sqrt(stiffness)),
921 conesJac_(), error_(Eigen::Vector3d::Zero()), errorD_(Eigen::Vector3d::Zero()), Q_(), C_()
925 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(begin_, begin_); }
927 void error(
const Eigen::Vector3d & error);
928 void errorD(
const Eigen::Vector3d & errorD);
930 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
931 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
932 const std::vector<rbd::MultiBodyConfig> & mbcs,
935 virtual const Eigen::MatrixXd & Q()
const override;
936 virtual const Eigen::VectorXd & C()
const override;
942 double stiffness_, stiffnessSqrt_;
943 Eigen::MatrixXd conesJac_;
944 Eigen::Vector3d error_, errorD_;
954 :
Task(weight), contactId_(contactId), origin_(origin), axis_(axis), begin_(0), Q_(), C_()
958 virtual std::pair<int, int>
begin()
const override {
return std::make_pair(begin_, begin_); }
960 virtual void updateNrVars(
const std::vector<rbd::MultiBody> & mbs,
const SolverData & data)
override;
961 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
962 const std::vector<rbd::MultiBodyConfig> & mbcs,
965 virtual const Eigen::MatrixXd & Q()
const override;
966 virtual const Eigen::VectorXd & C()
const override;
970 Eigen::Vector3d origin_;
971 Eigen::Vector3d axis_;
983 const std::string & bodyName,
984 const Eigen::Vector3d & vel,
985 const Eigen::Vector3d & bodyPoint = Eigen::Vector3d::Zero());
989 void velocity(
const Eigen::Vector3d & s) { pt_.velocity(s); }
991 const Eigen::Vector3d &
velocity()
const {
return pt_.velocity(); }
993 void bodyPoint(
const Eigen::Vector3d & point) { pt_.bodyPoint(point); }
995 const Eigen::Vector3d &
bodyPoint()
const {
return pt_.bodyPoint(); }
997 virtual int dim()
override;
998 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
999 const std::vector<rbd::MultiBodyConfig> & mbcs,
1002 virtual const Eigen::MatrixXd & jac()
const override;
1003 virtual const Eigen::VectorXd & eval()
const override;
1004 virtual const Eigen::VectorXd & speed()
const override;
1005 virtual const Eigen::VectorXd & normalAcc()
const override;
1017 const std::string & bodyName,
1018 const Eigen::Vector3d & bodyPoint,
1019 const Eigen::Vector3d & bodyAxis,
1020 const std::vector<std::string> & trackingJointsName,
1021 const Eigen::Vector3d & trackedPoint);
1027 const Eigen::Vector3d &
trackedPoint()
const {
return ott_.trackedPoint(); }
1029 void bodyPoint(
const Eigen::Vector3d & bp) { ott_.bodyPoint(bp); }
1031 const Eigen::Vector3d &
bodyPoint()
const {
return ott_.bodyPoint(); }
1033 void bodyAxis(
const Eigen::Vector3d & ba) { ott_.bodyAxis(ba); }
1035 const Eigen::Vector3d &
bodyAxis()
const {
return ott_.bodyAxis(); }
1037 virtual int dim()
override;
1038 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1039 const std::vector<rbd::MultiBodyConfig> & mbcs,
1042 virtual const Eigen::MatrixXd & jac()
const override;
1043 virtual const Eigen::VectorXd & eval()
const override;
1044 virtual const Eigen::VectorXd & speed()
const override;
1045 virtual const Eigen::VectorXd & normalAcc()
const override;
1050 Eigen::VectorXd alphaVec_;
1051 Eigen::VectorXd speed_, normalAcc_;
1059 const double timestep,
1062 const Eigen::Vector3d & u1 = Eigen::Vector3d::Zero(),
1063 const Eigen::Vector3d & u2 = Eigen::Vector3d::Zero());
1067 void robotPoint(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & point)
1069 int bIndex = mb.bodyIndexByName(bName);
1070 rdt_.robotPoint(bIndex, point);
1072 void envPoint(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & point)
1074 int bIndex = mb.bodyIndexByName(bName);
1075 rdt_.envPoint(bIndex, point);
1077 void vector(
const rbd::MultiBody & mb,
const std::string & bName,
const Eigen::Vector3d & u)
1079 int bIndex = mb.bodyIndexByName(bName);
1080 rdt_.vector(bIndex, u);
1083 virtual int dim()
override;
1084 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1085 const std::vector<rbd::MultiBodyConfig> & mbcs,
1088 virtual const Eigen::MatrixXd & jac()
const override;
1089 virtual const Eigen::VectorXd & eval()
const override;
1090 virtual const Eigen::VectorXd & speed()
const override;
1091 virtual const Eigen::VectorXd & normalAcc()
const override;
1103 const std::string & bodyName,
1104 const Eigen::Vector3d & bodyVector,
1105 const Eigen::Vector3d & targetVector);
1108 void bodyVector(
const Eigen::Vector3d & vector) { vot_.bodyVector(vector); }
1109 const Eigen::Vector3d &
bodyVector()
const {
return vot_.bodyVector(); }
1110 void target(
const Eigen::Vector3d & vector) { vot_.target(vector); }
1111 const Eigen::Vector3d &
target()
const {
return vot_.target(); }
1112 const Eigen::Vector3d &
actual()
const {
return vot_.actual(); }
1114 virtual int dim()
override;
1115 virtual void update(
const std::vector<rbd::MultiBody> & mbs,
1116 const std::vector<rbd::MultiBodyConfig> & mbcs,
1119 virtual const Eigen::MatrixXd & jac()
const override;
1120 virtual const Eigen::VectorXd & eval()
const override;
1121 virtual const Eigen::VectorXd & speed()
const override;
1122 virtual const Eigen::VectorXd & normalAcc()
const override;