/usr/include/kido/dynamics/Skeleton.hpp is in libkido-dev 0.1.0+dfsg-2build9.
This file is owned by root:root, with mode 0o644.
The actual contents of the file can be viewed below.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 | /*
* Copyright (c) 2011-2015, Georgia Tech Research Corporation
* All rights reserved.
*
* Author(s): Sehoon Ha <sehoon.ha@gmail.com>,
* Jeongseok Lee <jslee02@gmail.com>
*
* Georgia Tech Graphics Lab and Humanoid Robotics Lab
*
* Directed by Prof. C. Karen Liu and Prof. Mike Stilman
* <karenliu@cc.gatech.edu> <mstilman@cc.gatech.edu>
*
* This file is provided under the following "BSD-style" License:
* Redistribution and use in source and binary forms, with or
* without modification, are permitted provided that the following
* conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef KIDO_DYNAMICS_SKELETON_HPP_
#define KIDO_DYNAMICS_SKELETON_HPP_
#include <mutex>
#include "kido/common/NameManager.hpp"
#include "kido/dynamics/MetaSkeleton.hpp"
#include "kido/dynamics/SmartPointer.hpp"
#include "kido/dynamics/HierarchicalIK.hpp"
namespace kido {
namespace renderer {
class RenderInterface;
} // namespace renderer
} // namespace kido
namespace kido {
namespace dynamics {
class EndEffector;
/// class Skeleton
class Skeleton : public MetaSkeleton
{
public:
struct Properties
{
/// Name
std::string mName;
/// If the skeleton is not mobile, its dynamic effect is equivalent
/// to having infinite mass. If the configuration of an immobile skeleton is
/// manually changed, the collision results might not be correct.
bool mIsMobile;
/// Gravity vector.
Eigen::Vector3d mGravity;
/// Time step for implicit joint damping force.
double mTimeStep;
/// True if self collision check is enabled. Use mEnabledAdjacentBodyCheck
/// to disable collision checks between adjacent bodies.
bool mEnabledSelfCollisionCheck;
/// True if self collision check is enabled, including adjacent bodies.
/// Note: If mEnabledSelfCollisionCheck is false, then this value will be
/// ignored.
bool mEnabledAdjacentBodyCheck;
Properties(
const std::string& _name = "Skeleton",
bool _isMobile = true,
const Eigen::Vector3d& _gravity = Eigen::Vector3d(0.0, 0.0, -9.81),
double _timeStep = 0.001,
bool _enabledSelfCollisionCheck = false,
bool _enableAdjacentBodyCheck = false);
};
//----------------------------------------------------------------------------
/// \{ \name Constructor and Destructor
//----------------------------------------------------------------------------
/// Create a new Skeleton inside of a shared_ptr
static SkeletonPtr create(const std::string& _name="Skeleton");
/// Create a new Skeleton inside of a shared_ptr
static SkeletonPtr create(const Properties& _properties);
/// Get the shared_ptr that manages this Skeleton
SkeletonPtr getPtr();
/// Get the shared_ptr that manages this Skeleton
ConstSkeletonPtr getPtr() const;
/// Get the mutex that protects the state of this Skeleton
std::mutex& getMutex() const;
Skeleton(const Skeleton&) = delete;
/// Destructor
virtual ~Skeleton();
/// Remove copy operator
Skeleton& operator=(const Skeleton& _other) = delete;
/// Create an identical clone of this Skeleton.
///
/// Note: the state of the Skeleton will NOT be cloned, only the structure and
/// properties will be [TODO(MXG): copy the state as well]
SkeletonPtr clone() const;
/// \}
//----------------------------------------------------------------------------
/// \{ \name Properties
//----------------------------------------------------------------------------
/// Set the Properties of this Skeleton
void setProperties(const Properties& _properties);
/// Get the Properties of this Skeleton
const Properties& getSkeletonProperties() const;
/// Set name.
const std::string& setName(const std::string& _name) override;
/// Get name.
const std::string& getName() const override;
/// Enable self collision check
void enableSelfCollision(bool _enableAdjacentBodyCheck = false);
/// Disable self collision check
void disableSelfCollision();
/// Return true if self collision check is enabled
bool isEnabledSelfCollisionCheck() const;
/// Return true if self collision check is enabled including adjacent
/// bodies
bool isEnabledAdjacentBodyCheck() const;
/// Set whether this skeleton will be updated by forward dynamics.
/// \param[in] _isMobile True if this skeleton is mobile.
void setMobile(bool _isMobile);
/// Get whether this skeleton will be updated by forward dynamics.
/// \return True if this skeleton is mobile.
bool isMobile() const;
/// Set time step. This timestep is used for implicit joint damping
/// force.
void setTimeStep(double _timeStep);
/// Get time step.
double getTimeStep() const;
/// Set 3-dim gravitational acceleration. The gravity is used for
/// calculating gravity force vector of the skeleton.
void setGravity(const Eigen::Vector3d& _gravity);
/// Get 3-dim gravitational acceleration.
const Eigen::Vector3d& getGravity() const;
/// \}
//----------------------------------------------------------------------------
/// \{ \name Structural Properties
//----------------------------------------------------------------------------
#ifdef _WIN32
template <typename JointType>
static typename JointType::Properties createJointProperties()
{
return typename JointType::Properties();
}
template <typename NodeType>
static typename NodeType::Properties createBodyNodeProperties()
{
return typename NodeType::Properties();
}
#endif
// TODO: Workaround for MSVC bug on template function specialization with
// default argument. Please see #487 for detail
/// Create a Joint and child BodyNode pair of the given types. When creating
/// a root (parentless) BodyNode, pass in nullptr for the _parent argument.
template <class JointType, class NodeType = BodyNode>
std::pair<JointType*, NodeType*> createJointAndBodyNodePair(
BodyNode* _parent = nullptr,
#ifdef _WIN32
const typename JointType::Properties& _jointProperties
= Skeleton::createJointProperties<JointType>(),
const typename NodeType::Properties& _bodyProperties
= Skeleton::createBodyNodeProperties<NodeType>());
#else
const typename JointType::Properties& _jointProperties
= typename JointType::Properties(),
const typename NodeType::Properties& _bodyProperties
= typename NodeType::Properties());
#endif
// TODO: Workaround for MSVC bug on template function specialization with
// default argument. Please see #487 for detail
// Documentation inherited
size_t getNumBodyNodes() const override;
/// Get number of rigid body nodes.
size_t getNumRigidBodyNodes() const;
/// Get number of soft body nodes.
size_t getNumSoftBodyNodes() const;
/// Get the number of independent trees that this Skeleton contains
size_t getNumTrees() const;
/// Get the root BodyNode of the tree whose index in this Skeleton is _treeIdx
BodyNode* getRootBodyNode(size_t _treeIdx = 0);
/// Get the const root BodyNode of the tree whose index in this Skeleton is
/// _treeIdx
const BodyNode* getRootBodyNode(size_t _treeIdx = 0) const;
// Documentation inherited
BodyNode* getBodyNode(size_t _idx) override;
// Documentation inherited
const BodyNode* getBodyNode(size_t _idx) const override;
/// Get SoftBodyNode whose index is _idx
SoftBodyNode* getSoftBodyNode(size_t _idx);
/// Get const SoftBodyNode whose index is _idx
const SoftBodyNode* getSoftBodyNode(size_t _idx) const;
/// Get body node whose name is _name
BodyNode* getBodyNode(const std::string& _name);
/// Get const body node whose name is _name
const BodyNode* getBodyNode(const std::string& _name) const;
/// Get soft body node whose name is _name
SoftBodyNode* getSoftBodyNode(const std::string& _name);
/// Get const soft body node whose name is _name
const SoftBodyNode* getSoftBodyNode(const std::string& _name) const;
// Documentation inherited
const std::vector<BodyNode*>& getBodyNodes() override;
// Documentation inherited
const std::vector<const BodyNode*>& getBodyNodes() const override;
// Documentation inherited
size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override;
/// Get the BodyNodes belonging to a tree in this Skeleton
const std::vector<BodyNode*>& getTreeBodyNodes(size_t _treeIdx);
/// Get the BodyNodes belonging to a tree in this Skeleton
std::vector<const BodyNode*> getTreeBodyNodes(size_t _treeIdx) const;
// Documentation inherited
size_t getNumJoints() const override;
// Documentation inherited
Joint* getJoint(size_t _idx) override;
// Documentation inherited
const Joint* getJoint(size_t _idx) const override;
/// Get Joint whose name is _name
Joint* getJoint(const std::string& _name);
/// Get const Joint whose name is _name
const Joint* getJoint(const std::string& _name) const;
// Documentation inherited
size_t getIndexOf(const Joint* _joint, bool _warning=true) const override;
// Documentation inherited
size_t getNumDofs() const override;
// Documentation inherited
DegreeOfFreedom* getDof(size_t _idx) override;
// Documentation inherited
const DegreeOfFreedom* getDof(size_t _idx) const override;
/// Get degree of freedom (aka generalized coordinate) whose name is _name
DegreeOfFreedom* getDof(const std::string& _name);
/// Get degree of freedom (aka generalized coordinate) whose name is _name
const DegreeOfFreedom* getDof(const std::string& _name) const;
// Documentation inherited
const std::vector<DegreeOfFreedom*>& getDofs() override;
// Documentation inherited
std::vector<const DegreeOfFreedom*> getDofs() const override;
// Documentation inherited
size_t getIndexOf(const DegreeOfFreedom* _dof,
bool _warning=true) const override;
/// Get the DegreesOfFreedom belonging to a tree in this Skeleton
const std::vector<DegreeOfFreedom*>& getTreeDofs(size_t _treeIdx);
/// Get the DegreesOfFreedom belonging to a tree in this Skeleton
const std::vector<const DegreeOfFreedom*>& getTreeDofs(size_t _treeIdx) const;
/// Get the number of EndEffectors on this Skeleton
size_t getNumEndEffectors() const;
/// Get EndEffector whose index is _idx
EndEffector* getEndEffector(size_t _idx);
/// Get EndEffector whose index is _idx
const EndEffector* getEndEffector(size_t _idx) const;
/// Get EndEffector whose name is _name
EndEffector* getEndEffector(const std::string& _name);
/// Get EndEffector whose name is _name
const EndEffector* getEndEffector(const std::string &_name) const;
/// Get a pointer to a WholeBodyIK module for this Skeleton. If _createIfNull
/// is true, then the IK module will be generated if one does not already
/// exist.
const std::shared_ptr<WholeBodyIK>& getIK(bool _createIfNull = false);
/// Get a pointer to a WholeBodyIK module for this Skeleton. The IK module
/// will be generated if one does not already exist. This function is actually
/// the same as getIK(true).
const std::shared_ptr<WholeBodyIK>& getOrCreateIK();
/// Get a pointer to a WholeBodyIK module for this Skeleton. Because this is a
/// const function, a new IK module cannot be created if one does not already
/// exist.
std::shared_ptr<const WholeBodyIK> getIK() const;
/// Create a new WholeBodyIK module for this Skeleton. If an IK module already
/// exists in this Skeleton, it will be destroyed and replaced by a brand new
/// one.
const std::shared_ptr<WholeBodyIK>& createIK();
/// Wipe away the WholeBodyIK module for this Skeleton, leaving it as a
/// nullptr
void clearIK();
/// Get total number of markers in this Skeleton
size_t getNumMarkers() const;
/// Get marker whose name is _name
Marker* getMarker(const std::string& _name);
/// Get const marker whose name is _name
const Marker* getMarker(const std::string& _name) const;
/// \}
//----------------------------------------------------------------------------
// Integration and finite difference
//----------------------------------------------------------------------------
// Documentation inherited
void integratePositions(double _dt);
// Documentation inherited
void integrateVelocities(double _dt);
/// Return the difference of two generalized positions which are measured in
/// the configuration space of this Skeleton. If the configuration space is
/// Euclidean space, this function returns _q2 - _q1. Otherwise, it depends on
/// the type of the configuration space.
Eigen::VectorXd getPositionDifferences(
const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const;
/// Return the difference of two generalized velocities or accelerations which
/// are measured in the tangent space at the identity. Since the tangent
/// spaces are vector spaces, this function always returns _dq2 - _dq1.
Eigen::VectorXd getVelocityDifferences(
const Eigen::VectorXd& _dq2, const Eigen::VectorXd& _dq1) const;
//----------------------------------------------------------------------------
// State
//----------------------------------------------------------------------------
/// Set the state of this skeleton described in generalized coordinates
void setState(const Eigen::VectorXd& _state);
/// Get the state of this skeleton described in generalized coordinates
Eigen::VectorXd getState() const;
//----------------------------------------------------------------------------
/// \{ \name Support Polygon
//----------------------------------------------------------------------------
/// Get the support polygon of this Skeleton, which is computed based on the
/// gravitational projection of the support geometries of all EndEffectors
/// in this Skeleton that are currently in support mode.
const math::SupportPolygon& getSupportPolygon() const;
/// Same as getSupportPolygon(), but it will only use EndEffectors within the
/// specified tree within this Skeleton
const math::SupportPolygon& getSupportPolygon(size_t _treeIdx) const;
/// Get a list of the EndEffector indices that correspond to each of the
/// points in the support polygon.
const std::vector<size_t>& getSupportIndices() const;
/// Same as getSupportIndices(), but it corresponds to the support polygon of
/// the specified tree within this Skeleton
const std::vector<size_t>& getSupportIndices(size_t _treeIdx) const;
/// Get the axes that correspond to each component in the support polygon.
/// These axes are needed in order to map the points on a support polygon
/// into 3D space. If gravity is along the z-direction, then these axes will
/// simply be <1,0,0> and <0,1,0>.
const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes() const;
/// Same as getSupportAxes(), but it corresponds to the support polygon of the
/// specified tree within this Skeleton
const std::pair<Eigen::Vector3d, Eigen::Vector3d>& getSupportAxes(
size_t _treeIdx) const;
/// Get the centroid of the support polygon for this Skeleton. If the support
/// polygon is an empty set, the components of this vector will be nan.
const Eigen::Vector2d& getSupportCentroid() const;
/// Get the centroid of the support polygon for a tree in this Skeleton. If
/// the support polygon is an empty set, the components of this vector will be
/// nan.
const Eigen::Vector2d& getSupportCentroid(size_t _treeIdx) const;
/// The version number of a support polygon will be incremented each time the
/// support polygon needs to be recomputed. This number can be used to
/// immediately determine whether the support polygon has changed since the
/// last time you asked for it, allowing you to be more efficient in how you
/// handle the data.
size_t getSupportVersion() const;
/// Same as getSupportVersion(), but it corresponds to the support polygon of
/// the specified tree within this Skeleton
size_t getSupportVersion(size_t _treeIdx) const;
/// \}
//----------------------------------------------------------------------------
// Kinematics algorithms
//----------------------------------------------------------------------------
/// Compute forward kinematics
///
/// In general, this function doesn't need to be called for forward kinematics
/// to update. Forward kinematics will always be computed when it's needed and
/// will only perform the computations that are necessary for what the user
/// requests. This works by performing some bookkeeping internally with dirty
/// flags whenever a position, velocity, or acceleration is set, either
/// internally or by the user.
///
/// On one hand, this results in some overhead due to the extra effort of
/// bookkeeping, but on the other hand we have much greater code safety, and
/// in some cases performance can be dramatically improved with the auto-
/// updating. For example, this function is inefficient when only one portion
/// of the BodyNodes needed to be updated rather than the entire Skeleton,
/// which is common when performing inverse kinematics on a limb or on some
/// subsection of a Skeleton.
///
/// This function might be useful in a case where the user wants to perform
/// all the forward kinematics computations during a particular time window
/// rather than waiting for it to be computed at the exact time that it's
/// needed.
///
/// One example would be a real time controller. Let's say a controller gets
/// encoder data at time t0 but needs to wait until t1 before it receives the
/// force-torque sensor data that it needs in order to compute the output for
/// an operational space controller. Instead of being idle from t0 to t1, it
/// could use that time to compute the forward kinematics by calling this
/// function.
void computeForwardKinematics(bool _updateTransforms = true,
bool _updateVels = true,
bool _updateAccs = true);
//----------------------------------------------------------------------------
// Dynamics algorithms
//----------------------------------------------------------------------------
/// Compute forward dynamics
void computeForwardDynamics();
/// Compute inverse dynamics
void computeInverseDynamics(bool _withExternalForces = false,
bool _withDampingForces = false,
bool _withSpringForces = false);
//----------------------------------------------------------------------------
// Impulse-based dynamics algorithms
//----------------------------------------------------------------------------
/// Clear constraint impulses and cache data used for impulse-based forward
/// dynamics algorithm, where the constraint impulses are spatial constraints
/// on the BodyNodes and generalized constraints on the Joints.
void clearConstraintImpulses();
/// Update bias impulses
void updateBiasImpulse(BodyNode* _bodyNode);
/// \brief Update bias impulses due to impulse [_imp] on body node [_bodyNode]
/// \param _bodyNode Body node contraint impulse, _imp, is applied
/// \param _imp Constraint impulse expressed in body frame of _bodyNode
void updateBiasImpulse(BodyNode* _bodyNode, const Eigen::Vector6d& _imp);
/// \brief Update bias impulses due to impulse [_imp] on body node [_bodyNode]
/// \param _bodyNode Body node contraint impulse, _imp1, is applied
/// \param _imp Constraint impulse expressed in body frame of _bodyNode1
/// \param _bodyNode Body node contraint impulse, _imp2, is applied
/// \param _imp Constraint impulse expressed in body frame of _bodyNode2
void updateBiasImpulse(BodyNode* _bodyNode1, const Eigen::Vector6d& _imp1,
BodyNode* _bodyNode2, const Eigen::Vector6d& _imp2);
/// \brief Update bias impulses due to impulse[_imp] on body node [_bodyNode]
void updateBiasImpulse(SoftBodyNode* _softBodyNode,
PointMass* _pointMass,
const Eigen::Vector3d& _imp);
/// \brief Update velocity changes in body nodes and joints due to applied
/// impulse
void updateVelocityChange();
// TODO(JS): Better naming
/// Set whether this skeleton is constrained. ConstraintSolver will
/// mark this.
void setImpulseApplied(bool _val);
/// Get whether this skeleton is constrained
bool isImpulseApplied() const;
/// Compute impulse-based forward dynamics
void computeImpulseForwardDynamics();
//----------------------------------------------------------------------------
/// \{ \name Jacobians
//----------------------------------------------------------------------------
// Documentation inherited
math::Jacobian getJacobian(const JacobianNode* _node) const override;
// Documentation inherited
math::Jacobian getJacobian(
const JacobianNode* _node,
const Frame* _inCoordinatesOf) const override;
// Documentation inherited
math::Jacobian getJacobian(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset) const override;
// Documentation inherited
math::Jacobian getJacobian(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset,
const Frame* _inCoordinatesOf) const override;
// Documentation inherited
math::Jacobian getWorldJacobian(
const JacobianNode* _node) const override;
// Documentation inherited
math::Jacobian getWorldJacobian(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset) const override;
// Documentation inherited
math::LinearJacobian getLinearJacobian(
const JacobianNode* _node,
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::LinearJacobian getLinearJacobian(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset,
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::AngularJacobian getAngularJacobian(
const JacobianNode* _node,
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::Jacobian getJacobianSpatialDeriv(
const JacobianNode* _node) const override;
// Documentation inherited
math::Jacobian getJacobianSpatialDeriv(
const JacobianNode* _node,
const Frame* _inCoordinatesOf) const override;
// Documentation inherited
math::Jacobian getJacobianSpatialDeriv(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset) const override;
// Documentation inherited
math::Jacobian getJacobianSpatialDeriv(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset,
const Frame* _inCoordinatesOf) const override;
// Documentation inherited
math::Jacobian getJacobianClassicDeriv(
const JacobianNode* _node) const override;
// Documentation inherited
math::Jacobian getJacobianClassicDeriv(
const JacobianNode* _node,
const Frame* _inCoordinatesOf) const override;
// Documentation inherited
math::Jacobian getJacobianClassicDeriv(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset,
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::LinearJacobian getLinearJacobianDeriv(
const JacobianNode* _node,
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::LinearJacobian getLinearJacobianDeriv(
const JacobianNode* _node,
const Eigen::Vector3d& _localOffset = Eigen::Vector3d::Zero(),
const Frame* _inCoordinatesOf = Frame::World()) const override;
// Documentation inherited
math::AngularJacobian getAngularJacobianDeriv(
const JacobianNode* _node,
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// \}
//----------------------------------------------------------------------------
/// \{ \name Equations of Motion
//----------------------------------------------------------------------------
/// Get total mass of the skeleton. The total mass is calculated as BodyNodes
/// are added and is updated as BodyNode mass is changed, so this is a
/// constant-time O(1) operation for the Skeleton class.
double getMass() const override;
/// Get the mass matrix of a specific tree in the Skeleton
const Eigen::MatrixXd& getMassMatrix(size_t _treeIdx) const;
// Documentation inherited
const Eigen::MatrixXd& getMassMatrix() const override;
/// Get the augmented mass matrix of a specific tree in the Skeleton
const Eigen::MatrixXd& getAugMassMatrix(size_t _treeIdx) const;
// Documentation inherited
const Eigen::MatrixXd& getAugMassMatrix() const override;
/// Get the inverse mass matrix of a specific tree in the Skeleton
const Eigen::MatrixXd& getInvMassMatrix(size_t _treeIdx) const;
// Documentation inherited
const Eigen::MatrixXd& getInvMassMatrix() const override;
/// Get the inverse augmented mass matrix of a tree
const Eigen::MatrixXd& getInvAugMassMatrix(size_t _treeIdx) const;
// Documentation inherited
const Eigen::MatrixXd& getInvAugMassMatrix() const override;
/// Get the Coriolis force vector of a tree in this Skeleton
const Eigen::VectorXd& getCoriolisForces(size_t _treeIdx) const;
// Documentation inherited
const Eigen::VectorXd& getCoriolisForces() const override;
/// Get the gravity forces for a tree in this Skeleton
const Eigen::VectorXd& getGravityForces(size_t _treeIdx) const;
// Documentation inherited
const Eigen::VectorXd& getGravityForces() const override;
/// Get the combined vector of Coriolis force and gravity force of a tree
const Eigen::VectorXd& getCoriolisAndGravityForces(size_t _treeIdx) const;
// Documentation inherited
const Eigen::VectorXd& getCoriolisAndGravityForces() const override;
/// Get the external force vector of a tree in the Skeleton
const Eigen::VectorXd& getExternalForces(size_t _treeIdx) const;
// Documentation inherited
const Eigen::VectorXd& getExternalForces() const override;
/// Get damping force of the skeleton.
// const Eigen::VectorXd& getDampingForceVector();
/// Get constraint force vector for a tree
const Eigen::VectorXd& getConstraintForces(size_t _treeIdx) const;
/// Get constraint force vector
const Eigen::VectorXd& getConstraintForces() const override;
// Documentation inherited
void clearExternalForces() override;
// Documentation inherited
void clearInternalForces() override;
/// Notify that the articulated inertia and everything that depends on it
/// needs to be updated
void notifyArticulatedInertiaUpdate(size_t _treeIdx);
/// Notify that the support polygon of a tree needs to be updated
void notifySupportUpdate(size_t _treeIdx);
// Documentation inherited
double getKineticEnergy() const override;
// Documentation inherited
double getPotentialEnergy() const override;
/// \}
//----------------------------------------------------------------------------
/// \{ \name Center of Mass Jacobian
//----------------------------------------------------------------------------
/// Get the Skeleton's COM with respect to any Frame (default is World Frame)
Eigen::Vector3d getCOM(
const Frame* _withRespectTo = Frame::World()) const override;
/// Get the Skeleton's COM spatial velocity in terms of any Frame (default is
/// World Frame)
Eigen::Vector6d getCOMSpatialVelocity(
const Frame* _relativeTo = Frame::World(),
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM linear velocity in terms of any Frame (default is
/// World Frame)
Eigen::Vector3d getCOMLinearVelocity(
const Frame* _relativeTo = Frame::World(),
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM spatial acceleration in terms of any Frame (default
/// is World Frame)
Eigen::Vector6d getCOMSpatialAcceleration(
const Frame* _relativeTo = Frame::World(),
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM linear acceleration in terms of any Frame (default
/// is World Frame)
Eigen::Vector3d getCOMLinearAcceleration(
const Frame* _relativeTo = Frame::World(),
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM Jacobian in terms of any Frame (default is World
/// Frame)
math::Jacobian getCOMJacobian(
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM Linear Jacobian in terms of any Frame (default is
/// World Frame)
math::LinearJacobian getCOMLinearJacobian(
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM Jacobian spatial time derivative in terms of any
/// Frame (default is World Frame).
///
/// NOTE: Since this is a spatial time derivative, it is only meant to be used
/// with spatial acceleration vectors. If you are using classical linear
/// vectors, then use getCOMLinearJacobianDeriv() instead.
math::Jacobian getCOMJacobianSpatialDeriv(
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// Get the Skeleton's COM Linear Jacobian time derivative in terms of any
/// Frame (default is World Frame).
///
/// NOTE: Since this is a classical time derivative, it is only meant to be
/// used with classical acceleration vectors. If you are using spatial
/// vectors, then use getCOMJacobianSpatialDeriv() instead.
math::LinearJacobian getCOMLinearJacobianDeriv(
const Frame* _inCoordinatesOf = Frame::World()) const override;
/// \}
//----------------------------------------------------------------------------
// Rendering
//----------------------------------------------------------------------------
/// Draw this skeleton
void draw(renderer::RenderInterface* _ri = nullptr,
const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(),
bool _useDefaultColor = true) const;
/// Draw markers in this skeleton
void drawMarkers(renderer::RenderInterface* _ri = nullptr,
const Eigen::Vector4d& _color = Eigen::Vector4d::Ones(),
bool _useDefaultColor = true) const;
//----------------------------------------------------------------------------
// Friendship
//----------------------------------------------------------------------------
friend class BodyNode;
friend class SoftBodyNode;
friend class Joint;
friend class SingleDofJoint;
template<size_t> friend class MultiDofJoint;
friend class DegreeOfFreedom;
friend class EndEffector;
protected:
struct DataCache;
/// Constructor called by create()
Skeleton(const Properties& _properties);
/// Setup this Skeleton with its shared_ptr
void setPtr(const SkeletonPtr& _ptr);
/// Register a BodyNode with the Skeleton. Internal use only.
void registerBodyNode(BodyNode* _newBodyNode);
/// Register a Joint with the Skeleton. Internal use only.
void registerJoint(Joint* _newJoint);
/// Register an EndEffector with the Skeleton. Internal use only.
void registerEndEffector(EndEffector* _newEndEffector);
/// Remove a BodyNode from the Skeleton. Internal use only.
void unregisterBodyNode(BodyNode* _oldBodyNode);
/// Remove a Joint from the Skeleton. Internal use only.
void unregisterJoint(Joint* _oldJoint);
/// Remove an EndEffector from the Skeleton. Internal use only.
void unregisterEndEffector(EndEffector* _oldEndEffector);
/// Move a subtree of BodyNodes from this Skeleton to another Skeleton
bool moveBodyNodeTree(Joint* _parentJoint, BodyNode* _bodyNode,
SkeletonPtr _newSkeleton,
BodyNode* _parentNode);
/// Move a subtree of BodyNodes from this Skeleton to another Skeleton while
/// changing the Joint type of the top parent Joint.
///
/// Returns a nullptr if the move failed for any reason.
template <class JointType>
JointType* moveBodyNodeTree(
BodyNode* _bodyNode,
const SkeletonPtr& _newSkeleton,
BodyNode* _parentNode,
const typename JointType::Properties& _joint);
/// Copy a subtree of BodyNodes onto another Skeleton while leaving the
/// originals intact
std::pair<Joint*, BodyNode*> cloneBodyNodeTree(
Joint* _parentJoint,
const BodyNode* _bodyNode,
const SkeletonPtr& _newSkeleton,
BodyNode* _parentNode,
bool _recursive) const;
/// Copy a subtree of BodyNodes onto another Skeleton while leaving the
/// originals intact, but alter the top parent Joint to a new type
template <class JointType>
std::pair<JointType*, BodyNode*> cloneBodyNodeTree(
const BodyNode* _bodyNode,
const SkeletonPtr& _newSkeleton,
BodyNode* _parentNode,
const typename JointType::Properties& _joint,
bool _recursive) const;
/// Create a vector representation of a subtree of BodyNodes
std::vector<const BodyNode*> constructBodyNodeTree(
const BodyNode* _bodyNode) const;
std::vector<BodyNode*> constructBodyNodeTree(BodyNode* _bodyNode);
/// Create a vector representation of a subtree of BodyNodes and remove that
/// subtree from this Skeleton without deleting them
std::vector<BodyNode*> extractBodyNodeTree(BodyNode* _bodyNode);
/// Take in and register a subtree of BodyNodes
void receiveBodyNodeTree(const std::vector<BodyNode*>& _tree);
/// Update the computation for total mass
void updateTotalMass();
/// Update the dimensions for a specific cache
void updateCacheDimensions(DataCache& _cache);
/// Update the dimensions for a tree's cache
void updateCacheDimensions(size_t _treeIdx);
/// Update the articulated inertia of a tree
void updateArticulatedInertia(size_t _tree) const;
/// Update the articulated inertias of the skeleton
void updateArticulatedInertia() const;
/// Update the mass matrix of a tree
void updateMassMatrix(size_t _treeIdx) const;
/// Update mass matrix of the skeleton.
void updateMassMatrix() const;
void updateAugMassMatrix(size_t _treeIdx) const;
/// Update augmented mass matrix of the skeleton.
void updateAugMassMatrix() const;
/// Update the inverse mass matrix of a tree
void updateInvMassMatrix(size_t _treeIdx) const;
/// Update inverse of mass matrix of the skeleton.
void updateInvMassMatrix() const;
/// Update the inverse augmented mass matrix of a tree
void updateInvAugMassMatrix(size_t _treeIdx) const;
/// Update inverse of augmented mass matrix of the skeleton.
void updateInvAugMassMatrix() const;
/// Update Coriolis force vector for a tree in the Skeleton
void updateCoriolisForces(size_t _treeIdx) const;
/// Update Coriolis force vector of the skeleton.
void updateCoriolisForces() const;
/// Update the gravity force vector of a tree
void updateGravityForces(size_t _treeIdx) const;
/// Update gravity force vector of the skeleton.
void updateGravityForces() const;
/// Update the combined vector for a tree in this Skeleton
void updateCoriolisAndGravityForces(size_t _treeIdx) const;
/// Update combined vector of the skeleton.
void updateCoriolisAndGravityForces() const;
/// Update external force vector to generalized forces for a tree
void updateExternalForces(size_t _treeIdx) const;
// TODO(JS): Not implemented yet
/// update external force vector to generalized forces.
void updateExternalForces() const;
/// Compute the constraint force vector for a tree
const Eigen::VectorXd& computeConstraintForces(DataCache& cache) const;
// /// Update damping force vector.
// virtual void updateDampingForceVector();
/// Add a BodyNode to the BodyNode NameManager
const std::string& addEntryToBodyNodeNameMgr(BodyNode* _newNode);
/// Add a Joint to to the Joint NameManager
const std::string& addEntryToJointNameMgr(Joint* _newJoint, bool _updateDofNames=true);
/// Add an EndEffector to the EndEffector NameManager
void addEntryToEndEffectorNameMgr(EndEffector* _ee);
/// Add a SoftBodyNode to the SoftBodyNode NameManager
void addEntryToSoftBodyNodeNameMgr(SoftBodyNode* _newNode);
/// Add entries for all the Markers belonging to BodyNode _node
void addMarkersOfBodyNode(BodyNode* _node);
/// Remove entries for all the Markers belonging to BodyNode _node
void removeMarkersOfBodyNode(BodyNode* _node);
/// Add a Marker entry
const std::string& addEntryToMarkerNameMgr(Marker* _newMarker);
protected:
/// Properties of this Skeleton
Properties mSkeletonP;
/// The resource-managing pointer to this Skeleton
std::weak_ptr<Skeleton> mPtr;
/// List of Soft body node list in the skeleton
std::vector<SoftBodyNode*> mSoftBodyNodes;
/// List of EndEffectors in the Skeleton
std::vector<EndEffector*> mEndEffectors;
/// NameManager for tracking BodyNodes
kido::common::NameManager<BodyNode*> mNameMgrForBodyNodes;
/// NameManager for tracking Joints
kido::common::NameManager<Joint*> mNameMgrForJoints;
/// NameManager for tracking DegreesOfFreedom
kido::common::NameManager<DegreeOfFreedom*> mNameMgrForDofs;
/// NameManager for tracking SoftBodyNodes
kido::common::NameManager<SoftBodyNode*> mNameMgrForSoftBodyNodes;
/// NameManager for tracking Markers
kido::common::NameManager<Marker*> mNameMgrForMarkers;
/// NameManager for tracking EndEffectors
kido::common::NameManager<EndEffector*> mNameMgrForEndEffectors;
/// WholeBodyIK module for this Skeleton
std::shared_ptr<WholeBodyIK> mWholeBodyIK;
struct DirtyFlags
{
/// Default constructor
DirtyFlags();
/// Dirty flag for articulated body inertia
bool mArticulatedInertia;
/// Dirty flag for the mass matrix.
bool mMassMatrix;
/// Dirty flag for the mass matrix.
bool mAugMassMatrix;
/// Dirty flag for the inverse of mass matrix.
bool mInvMassMatrix;
/// Dirty flag for the inverse of augmented mass matrix.
bool mInvAugMassMatrix;
/// Dirty flag for the gravity force vector.
bool mGravityForces;
/// Dirty flag for the Coriolis force vector.
bool mCoriolisForces;
/// Dirty flag for the combined vector of Coriolis and gravity.
bool mCoriolisAndGravityForces;
/// Dirty flag for the external force vector.
bool mExternalForces;
/// Dirty flag for the damping force vector.
bool mDampingForces;
/// Dirty flag for the support polygon
bool mSupport;
/// Increments each time a new support polygon is computed to help keep
/// track of changes in the support polygon
size_t mSupportVersion;
};
struct DataCache
{
DirtyFlags mDirty;
/// BodyNodes belonging to this tree
std::vector<BodyNode*> mBodyNodes;
/// Cache for const BodyNodes, for the sake of the API
std::vector<const BodyNode*> mConstBodyNodes;
/// Degrees of Freedom belonging to this tree
std::vector<DegreeOfFreedom*> mDofs;
/// Cache for const Degrees of Freedom, for the sake of the API
std::vector<const DegreeOfFreedom*> mConstDofs;
/// Mass matrix cache
Eigen::MatrixXd mM;
/// Mass matrix for the skeleton.
Eigen::MatrixXd mAugM;
/// Inverse of mass matrix for the skeleton.
Eigen::MatrixXd mInvM;
/// Inverse of augmented mass matrix for the skeleton.
Eigen::MatrixXd mInvAugM;
/// Coriolis vector for the skeleton which is C(q,dq)*dq.
Eigen::VectorXd mCvec;
/// Gravity vector for the skeleton; computed in nonrecursive
/// dynamics only.
Eigen::VectorXd mG;
/// Combined coriolis and gravity vector which is C(q, dq)*dq + g(q).
Eigen::VectorXd mCg;
/// External force vector for the skeleton.
Eigen::VectorXd mFext;
/// Constraint force vector.
Eigen::VectorXd mFc;
/// Support polygon
math::SupportPolygon mSupportPolygon;
/// A map of which EndEffectors correspond to the individual points in the
/// support polygon
std::vector<size_t> mSupportIndices;
/// A pair of vectors which map the 2D coordinates of the support polygon
/// into 3D space
std::pair<Eigen::Vector3d, Eigen::Vector3d> mSupportAxes;
/// Support geometry -- only used for temporary storage purposes
math::SupportGeometry mSupportGeometry;
/// Centroid of the support polygon
Eigen::Vector2d mSupportCentroid;
// To get byte-aligned Eigen vectors
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
mutable Eigen::aligned_vector<DataCache> mTreeCache;
mutable DataCache mSkelCache;
/// Total mass.
double mTotalMass;
// TODO(JS): Better naming
/// Flag for status of impulse testing.
bool mIsImpulseApplied;
mutable std::mutex mMutex;
public:
//--------------------------------------------------------------------------
// Union finding
//--------------------------------------------------------------------------
///
void resetUnion()
{
mUnionRootSkeleton = mPtr;
mUnionSize = 1;
}
///
std::weak_ptr<Skeleton> mUnionRootSkeleton;
///
size_t mUnionSize;
///
size_t mUnionIndex;
public:
// To get byte-aligned Eigen vectors
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
#include "kido/dynamics/detail/Skeleton.hpp"
} // namespace dynamics
} // namespace kido
#endif // KIDO_DYNAMICS_SKELETON_HPP_
|