| XBotInterface
    2.4.1
    XBotInterface provides a generic API to model and control a robot. | 
ModelInterface is an abstraction layer for a kinematic/dynamic model of a robot. More...
#include <ModelInterface.h>
 Inheritance diagram for XBot::ModelInterface:
 Inheritance diagram for XBot::ModelInterface: Collaboration diagram for XBot::ModelInterface:
 Collaboration diagram for XBot::ModelInterface:| Public Types | |
| typedef std::shared_ptr< ModelInterface > | Ptr | 
| Shared pointer to a ModelInterface.  More... | |
| typedef std::shared_ptr< const ModelInterface > | ConstPtr | 
| Shared pointer to const ModelInterface.  More... | |
|  Public Types inherited from XBot::XBotInterface | |
| typedef std::shared_ptr< XBotInterface > | Ptr | 
| typedef std::shared_ptr< const XBotInterface > | ConstPtr | 
| Public Member Functions | |
| ModelInterface ()=default | |
| ModelInterface & | operator= (const ModelInterface &other)=delete | 
| ModelInterface (const ModelInterface &other)=delete | |
| ModelChain & | chain (const std::string &chain_name) | 
| Returns a handle to the kinematic chain named chain_name.  More... | |
| const ModelChain & | chain (const std::string &chain_name) const | 
| ModelChain & | operator() (const std::string &chain_name) | 
| Returns a handle to the kinematic chain named chain_name.  More... | |
| const ModelChain & | operator() (const std::string &chain_name) const | 
| ModelChain & | arm (int arm_id) | 
| Returns a handle to the kinematic chain corresponding to the arm n° arm_id.  More... | |
| const ModelChain & | arm (int arm_id) const | 
| ModelChain & | leg (int leg_id) | 
| Returns a handle to the kinematic chain corresponding to the leg n° leg_id.  More... | |
| const ModelChain & | leg (int leg_id) const | 
| template<typename... SyncFlags> | |
| bool | syncFrom (const XBotInterface &other, SyncFlags... flags) | 
| Synchronizes the internal model state to the one of the XBotInterface given as an argument.  More... | |
| template<typename... SyncFlags> | |
| bool | syncFrom_no_update (const XBotInterface &other, SyncFlags... flags) | 
| Synchronizes the internal model state to the one of the XBotInterface given as an argument.  More... | |
| bool | update (bool update_position=true, bool update_velocity=true, bool update_desired_acceleration=true) | 
| Updates the kinematic variables of the model according to the current state of the model.  More... | |
| virtual void | getModelOrderedJoints (std::vector< std::string > &joint_name) const =0 | 
| Gets a vector with the joint names ordered according to the model.  More... | |
| int | getActuatedJointNum () const | 
| Gets the number of actuated joints in the model, i.e.  More... | |
| bool | isFloatingBase () const | 
| True if the robot is floating base, false if it has a fixed base.  More... | |
| virtual bool | setFloatingBasePose (const KDL::Frame &floating_base_pose)=0 | 
| Sets the floating base pose w.r.t.  More... | |
| bool | setFloatingBaseOrientation (const KDL::Rotation &world_R_floating_base) | 
| Sets the floating base orientation w.r.t.  More... | |
| bool | getFloatingBasePose (KDL::Frame &floating_base_pose) const | 
| Gets the floating base pose w.r.t.  More... | |
| virtual bool | setFloatingBaseTwist (const KDL::Twist &floating_base_twist)=0 | 
| Sets the floating base twist w.r.t.  More... | |
| bool | setFloatingBaseAngularVelocity (const KDL::Vector &floating_base_omega) | 
| Sets the floating base angular velocity w.r.t.  More... | |
| bool | setFloatingBaseState (const KDL::Frame &pose, const KDL::Twist &twist) | 
| Sets the floating base pose and twist w.r.t.  More... | |
| bool | setFloatingBaseState (XBot::ImuSensor::ConstPtr imu, const Eigen::Matrix3d &offset=Eigen::Matrix3d::Identity()) | 
| Sets the floating base orientation and angular velocity w.r.t.  More... | |
| bool | getFloatingBaseTwist (KDL::Twist &floating_base_twist) const | 
| Gets the floating base twist w.r.t.  More... | |
| virtual bool | getFloatingBaseLink (std::string &floating_base_link) const =0 | 
| Gets the name of the floating base link.  More... | |
| virtual bool | getPose (const std::string &source_frame, KDL::Frame &pose) const =0 | 
| Computes the pose of the source_frame w.r.t.  More... | |
| bool | getPose (const std::string &source_frame, const std::string &target_frame, KDL::Frame &pose) const | 
| Computes the pose of the source_frame w.r.t.  More... | |
| bool | getOrientation (const std::string &source_frame, KDL::Rotation &orientation) const | 
| Computes the orientation of the source_frame w.r.t.  More... | |
| bool | getOrientation (const std::string &source_frame, const std::string &target_frame, KDL::Rotation &orientation) const | 
| Computes the orientation of the target_frame w.r.t.  More... | |
| bool | getPointPosition (const std::string &source_frame, const KDL::Vector &source_point, KDL::Vector &world_point) const | 
| Gets the position in world coordinates for a source_point expressed w.r.t.  More... | |
| bool | getPointPosition (const std::string &source_frame, const std::string &target_frame, const KDL::Vector &source_point, KDL::Vector &target_point) const | 
| Gets the position in target_frame coordinates for a source_point expressed w.r.t.  More... | |
| virtual bool | getJacobian (const std::string &link_name, const KDL::Vector &reference_point, KDL::Jacobian &J) const =0 | 
| Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.  More... | |
| bool | getJacobian (const std::string &link_name, KDL::Jacobian &J) const | 
| Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.  More... | |
| bool | getJacobian (const std::string &link_name, const std::string &target_frame, KDL::Jacobian &J) const | 
| Gets the Jacobian of link_name expressed in the target_frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name according to target_frame (i.e.  More... | |
| void | getPosturalJacobian (Eigen::MatrixXd &J) const | 
| Gets the Jacacobian matrix corresponding to a joint-space postural task, i.e.  More... | |
| virtual bool | getRelativeJacobian (const std::string &target_link_name, const std::string &base_link_name, KDL::Jacobian &J) const | 
| Gets the relative Jacobian of target_link_name w.r.t to base_link_name.  More... | |
| virtual bool | getVelocityTwist (const std::string &link_name, KDL::Twist &velocity) const =0 | 
| Gets the velocity twist of link_name (first linear, then angular velocity).  More... | |
| bool | getRelativeVelocityTwist (const std::string &link_name, const std::string &base_link_name, KDL::Twist &velocity) const | 
| Gets the velocity twist of link_name (first linear, then angular velocity) w.r.t.  More... | |
| virtual bool | getVelocityTwist (const std::string &source_frame, const std::string &target_frame, KDL::Twist &velocity) const | 
| Computes the velocity of the source_frame w.r.t.  More... | |
| virtual bool | getAccelerationTwist (const std::string &link_name, KDL::Twist &acceleration) const =0 | 
| Gets the acceleration twist of link_name (first linear, then angular acceleration).  More... | |
| virtual bool | getRelativeAccelerationTwist (const std::string &link_name, const std::string &base_link_name, KDL::Twist &acceleration) const =0 | 
| getRelativeAccelerationTwist compute the relative acceleration of body "link" wrt body "base_link" expressed in frame "base_link"  More... | |
| virtual bool | getPointAcceleration (const std::string &link_name, const KDL::Vector &point, KDL::Vector &acceleration) const =0 | 
| Gets the acceleration of a given point which is solidal with the given link.  More... | |
| virtual bool | computeJdotQdot (const std::string &link_name, const KDL::Vector &point, KDL::Twist &jdotqdot) const | 
| Computed the product of the link_name jacobian time derivative by the joint velocity vector.  More... | |
| virtual bool | computeRelativeJdotQdot (const std::string &target_link_name, const std::string &base_link_name, KDL::Twist &jdotqdot) const =0 | 
| computeRelativeJdotQdot return the relative acceleration component between "target_link" and "base_link", given by JdotQdot, expressed in "base_link"  More... | |
| virtual void | getCOM (KDL::Vector &com_position) const =0 | 
| Gets the COM position vector w.r.t.  More... | |
| bool | getCOM (const std::string &reference_frame, KDL::Vector &com_position) const | 
| Gets the COM position vector w.r.t.  More... | |
| virtual void | getCOMJacobian (KDL::Jacobian &J, KDL::Vector &dJcomQdot) const | 
| Gets the COM Jacobian expressed in the world frame and the d(Jcom)/dt * qdot term, i.e.  More... | |
| virtual void | getCOMJacobian (KDL::Jacobian &J) const | 
| Gets the COM Jacobian expressed in the world frame.  More... | |
| virtual void | getCOMVelocity (KDL::Vector &velocity) const =0 | 
| Gets the COM velocity expressed in the world frame.  More... | |
| virtual void | getCOMAcceleration (KDL::Vector &acceleration) const =0 | 
| Gets the COM acceleration expressed in the world frame.  More... | |
| virtual void | getCentroidalMomentum (Eigen::Vector6d ¢roidal_momentum) const =0 | 
| Gets the robot centroidal momentum matrix, i.e.  More... | |
| virtual void | getCentroidalMomentumMatrix (Eigen::MatrixXd ¢roidal_momentum_matrix, Eigen::Vector6d &CMMdotQdot) const | 
| Gets the robot centroidal momentum matrix, i.e.  More... | |
| virtual void | getCentroidalMomentumMatrix (Eigen::MatrixXd ¢roidal_momentum_matrix) const | 
| Gets the robot mometum about its COM.  More... | |
| virtual double | getMass () const =0 | 
| Gets the weight of the robot.  More... | |
| virtual void | getGravity (KDL::Vector &gravity) const =0 | 
| Gets the gravity vector expressed in the world frame.  More... | |
| bool | getGravity (const std::string &reference_frame, KDL::Vector &gravity) const | 
| Gets the gravity vector expressed in the reference_frame.  More... | |
| virtual void | setGravity (const KDL::Vector &gravity)=0 | 
| Sets the gravity vector expressed in the world frame.  More... | |
| bool | setGravity (const std::string &reference_frame, const KDL::Vector &gravity) | 
| Sets the gravity vector expressed in the reference_frame.  More... | |
| virtual void | getInertiaMatrix (Eigen::MatrixXd &M) const =0 | 
| Gets the joint space inertia matrix of the robot.  More... | |
| virtual void | getInertiaInverseTimesVector (const Eigen::VectorXd &vec, Eigen::VectorXd &minv_vec) const | 
| getInertiaInverseTimesVector Computes the inverse of the Inertia Matrix times a given vector  More... | |
| virtual void | getInertiaInverseTimesMatrix (const Eigen::MatrixXd &Mat, Eigen::MatrixXd &Minv_Mat) const | 
| getInertiaInverseTimesMatrix Computes the inverse of the Inertia Matrix times a given matrix  More... | |
| virtual void | getInertiaInverse (Eigen::MatrixXd &Minv) const | 
| getInertiaInverse compute the inverse of the Inertia Matrix  More... | |
| virtual void | computeGravityCompensation (Eigen::VectorXd &g) const =0 | 
| Computes gravity compensation torques.  More... | |
| virtual void | computeNonlinearTerm (Eigen::VectorXd &n) const =0 | 
| Computes the non-linear torque term without the contribution from gravity, i.e.  More... | |
| virtual void | computeInverseDynamics (Eigen::VectorXd &tau) const =0 | 
| Computes inverse dynamics.  More... | |
| bool | computeConstrainedInverseDynamics (const Eigen::MatrixXd &J, const Eigen::VectorXd &weights, Eigen::VectorXd &tau) const | 
| Computes inverse dynamics for a constrained system.  More... | |
| bool | getChainSelectionMatrix (const std::string &chain_name, Eigen::MatrixXd &S) const | 
| Gets a selection matrix for the requested chain, i.e.  More... | |
| bool | getJointSelectionMatrix (const std::string &joint_name, Eigen::RowVectorXd &S) const | 
| Gets a selection matrix for the requested joint, i.e.  More... | |
| bool | getJointSelectionMatrix (int joint_id, Eigen::RowVectorXd &S) const | 
| Gets a selection matrix for the requested joint, i.e.  More... | |
| bool | maskJacobian (const std::string &chain_name, KDL::Jacobian &J) const | 
| Applies a mask corresponding to the specified chain to the jacobian provided as an argument.  More... | |
| bool | setFloatingBasePose (const Eigen::Affine3d &floating_base_pose) | 
| Sets the floating base pose w.r.t.  More... | |
| bool | setFloatingBaseState (const Eigen::Affine3d &pose, const Eigen::Vector6d &twist) | 
| Sets the floating base pose and twist w.r.t.  More... | |
| bool | setFloatingBaseOrientation (const Eigen::Matrix3d &world_R_floating_base) | 
| Sets the floating base orientation w.r.t.  More... | |
| virtual bool | setFloatingBaseTwist (const Eigen::Vector6d &floating_base_twist) | 
| Sets the floating base twist w.r.t.  More... | |
| bool | setFloatingBaseAngularVelocity (const Eigen::Vector3d &floating_base_omega) | 
| Sets the floating base angular velocity w.r.t.  More... | |
| bool | getFloatingBasePose (Eigen::Affine3d &floating_base_pose) const | 
| Gets the floating base pose w.r.t.  More... | |
| bool | getFloatingBaseTwist (Eigen::Vector6d &floating_base_twist) const | 
| Gets the floating base twist w.r.t.  More... | |
| bool | getPose (const std::string &source_frame, const std::string &target_frame, Eigen::Affine3d &pose) const | 
| Computes the pose of the source_frame w.r.t.  More... | |
| bool | getPose (const std::string &source_frame, Eigen::Affine3d &pose) const | 
| Computes the pose of the source_frame w.r.t.  More... | |
| bool | getOrientation (const std::string &source_frame, Eigen::Matrix3d &orientation) const | 
| Computes the orientation of the source_frame w.r.t.  More... | |
| bool | getOrientation (const std::string &source_frame, const std::string &target_frame, Eigen::Matrix3d &orientation) const | 
| Computes the orientation of the source_frame w.r.t.  More... | |
| bool | getPointPosition (const std::string &source_frame, const Eigen::Vector3d &source_point, Eigen::Vector3d &world_point) const | 
| Gets the position in world coordinates for a source_point expressed w.r.t.  More... | |
| bool | getPointPosition (const std::string &source_frame, const std::string &target_frame, const Eigen::Vector3d &source_point, Eigen::Vector3d &target_point) const | 
| Gets the position in target_frame coordinates for a source_point expressed w.r.t.  More... | |
| bool | getJacobian (const std::string &link_name, Eigen::MatrixXd &J) const | 
| Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.  More... | |
| bool | getJacobian (const std::string &link_name, const std::string &target_frame, Eigen::MatrixXd &J) const | 
| Gets the Jacobian of link_name expressed in the target_frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name according to target_frame (i.e.  More... | |
| bool | getJacobian (const std::string &link_name, const Eigen::Vector3d &reference_point, Eigen::MatrixXd &J) const | 
| Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.  More... | |
| bool | getRelativeJacobian (const std::string &target_link_name, const std::string &base_link_name, Eigen::MatrixXd &J) const | 
| Gets the relative Jacobian of target_link_name w.r.t to base_link_name.  More... | |
| void | getCOM (Eigen::Vector3d &com_position) const | 
| Gets the COM position vector w.r.t.  More... | |
| bool | getCOM (const std::string &reference_frame, Eigen::Vector3d &com_position) const | 
| Gets the COM position vector w.r.t.  More... | |
| virtual void | getCOMJacobian (Eigen::MatrixXd &J, Eigen::Vector3d &dJcomQdot) const | 
| Gets the COM Jacobian expressed in the world frame and the d(Jcom)/dt * qdot term, i.e.  More... | |
| void | getCOMJacobian (Eigen::MatrixXd &J) const | 
| Gets the COM Jacobian expressed in the world frame.  More... | |
| void | getCOMVelocity (Eigen::Vector3d &velocity) const | 
| Gets the COM velocity expressed in the world frame.  More... | |
| void | getCOMAcceleration (Eigen::Vector3d &acceleration) const | 
| Gets the COM acceleration expressed in the world frame.  More... | |
| bool | getRelativeVelocityTwist (const std::string &link_name, const std::string &base_link_name, Eigen::Vector6d &velocity) const | 
| Gets the velocity twist of link_name (first linear, then angular velocity) w.r.t.  More... | |
| bool | getRelativeAccelerationTwist (const std::string &link_name, const std::string &base_link_name, Eigen::Vector6d &acceleration) const | 
| getRelativeAccelerationTwist compute the relative acceleration of body "link" wrt body "base_link" expressed in frame "base_link"  More... | |
| bool | getVelocityTwist (const std::string &link_name, Eigen::Vector6d &velocity) const | 
| Gets the velocity twist of link_name (first linear, then angular velocity).  More... | |
| virtual bool | getVelocityTwist (const std::string &source_frame, const std::string &target_frame, Eigen::Matrix< double, 6, 1 > &velocity) const | 
| Computes the velocity of the source_frame w.r.t.  More... | |
| bool | getAccelerationTwist (const std::string &link_name, Eigen::Vector6d &acceleration) const | 
| Gets the acceleration twist of link_name (first linear, then angular acceleration).  More... | |
| bool | getPointAcceleration (const std::string &link_name, const Eigen::Vector3d &point, Eigen::Vector3d &acceleration) const | 
| Gets the acceleration of a given point which is solidal with the given link.  More... | |
| bool | computeJdotQdot (const std::string &link_name, const Eigen::Vector3d &point, Eigen::Vector6d &jdotqdot) const | 
| Computed the product of the link_name jacobian time derivative by the joint velocity vector.  More... | |
| bool | computeRelativeJdotQdot (const std::string &target_link_name, const std::string &base_link_name, Eigen::Vector6d &jdotqdot) const | 
| computeRelativeJdotQdot return the relative acceleration component between "target_link" and "base_link", given by JdotQdot, expressed in "base_link"  More... | |
| void | getGravity (Eigen::Vector3d &gravity) const | 
| Gets the gravity vector expressed in the world frame.  More... | |
| bool | getGravity (const std::string &reference_frame, Eigen::Vector3d &gravity) const | 
| Gets the gravity vector expressed in the reference_frame.  More... | |
| void | setGravity (const Eigen::Vector3d &gravity) | 
| Sets the gravity vector expressed in the world frame.  More... | |
| bool | setGravity (const std::string &reference_frame, const Eigen::Vector3d &gravity) | 
| Sets the gravity vector expressed in the reference_frame.  More... | |
| bool | maskJacobian (const std::string &chain_name, Eigen::MatrixXd &J) const | 
| Applies a mask corresponding to the specified chain to the jacobian provided as an argument.  More... | |
| virtual int | getLinkID (const std::string &link_name) const =0 | 
| getLinkID return the link ID  More... | |
| bool | getJointPosition (Eigen::VectorXd &q) const | 
| Gets the robot joint positions as an Eigen vector.  More... | |
| bool | getJointPosition (JointIdMap &q) const | 
| Gets the robot joint positions as a JointIdMap, i.e.  More... | |
| bool | getJointPosition (JointNameMap &q) const | 
| Gets the robot joint postions as a JointNameMap, i.e.  More... | |
| bool | getMotorPosition (Eigen::VectorXd &q) const | 
| Gets the robot motor positions as an Eigen vector.  More... | |
| bool | getMotorPosition (JointIdMap &q) const | 
| Gets the robot motor positions as a JointIdMap, i.e.  More... | |
| bool | getMotorPosition (JointNameMap &q) const | 
| Gets the robot motor postions as a JointNameMap, i.e.  More... | |
| bool | getJointVelocity (Eigen::VectorXd &qdot) const | 
| Gets the robot joint velocities as an Eigen vector.  More... | |
| bool | getJointVelocity (JointIdMap &qdot) const | 
| Gets the robot joint velocities as a JointIdMap, i.e.  More... | |
| bool | getJointVelocity (JointNameMap &qdot) const | 
| Gets the robot joint velocities as a JointNameMap, i.e.  More... | |
| bool | getMotorVelocity (Eigen::VectorXd &qdot) const | 
| Gets the robot motor velocities as an Eigen vector.  More... | |
| bool | getMotorVelocity (JointIdMap &qdot) const | 
| Gets the robot motor velocities as a JointIdMap, i.e.  More... | |
| bool | getMotorVelocity (JointNameMap &qdot) const | 
| Gets the robot motor velocities as a JointNameMap, i.e.  More... | |
| bool | getJointAcceleration (Eigen::VectorXd &qddot) const | 
| Gets the robot joint accelerations as an Eigen vector.  More... | |
| bool | getJointAcceleration (JointIdMap &qddot) const | 
| Gets the robot joint accelerations as a JointIdMap, i.e.  More... | |
| bool | getJointAcceleration (JointNameMap &qddot) const | 
| Gets the robot joint accelerations as a JointNameMap, i.e.  More... | |
| bool | getJointEffort (Eigen::VectorXd &tau) const | 
| Gets the robot joint efforts as an Eigen vector.  More... | |
| bool | getJointEffort (JointIdMap &tau) const | 
| Gets the robot joint efforts as a JointIdMap, i.e.  More... | |
| bool | getJointEffort (JointNameMap &tau) const | 
| Gets the robot joint efforts as a JointNameMap, i.e.  More... | |
| bool | getStiffness (Eigen::VectorXd &K) const | 
| Gets the robot stiffness as an Eigen vector.  More... | |
| bool | getStiffness (JointIdMap &K) const | 
| Gets the robot stiffness as a JointIdMap, i.e.  More... | |
| bool | getStiffness (JointNameMap &K) const | 
| Gets the robot stiffness as a JointNameMap, i.e.  More... | |
| bool | getDamping (Eigen::VectorXd &D) const | 
| Gets the robot damping as an Eigen vector.  More... | |
| bool | getDamping (JointIdMap &D) const | 
| Gets the robot damping as a JointIdMap, i.e.  More... | |
| bool | getDamping (JointNameMap &D) const | 
| Gets the robot damping as a JointNameMap, i.e.  More... | |
| bool | setJointPosition (const Eigen::VectorXd &q) | 
| Sets the XBotInterface internal joint positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointPosition (const JointIdMap &q) | 
| Sets the XBotInterface internal joint positions according to the input JointIdMap (i.e.  More... | |
| bool | setJointPosition (const JointNameMap &q) | 
| Sets the XBotInterface internal joint positions according to the input JointNameMap (i.e.  More... | |
| bool | setMotorPosition (const Eigen::VectorXd &q) | 
| Sets the XBotInterface internal motor positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setMotorPosition (const JointIdMap &q) | 
| Sets the XBotInterface internal motor positions according to the input JointIdMap (i.e.  More... | |
| bool | setMotorPosition (const JointNameMap &q) | 
| Sets the XBotInterface internal motor positions according to the input JointNameMap (i.e.  More... | |
| bool | setJointVelocity (const Eigen::VectorXd &qdot) | 
| Sets the XBotInterface internal joint velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointVelocity (const JointIdMap &qdot) | 
| Sets the XBotInterface internal joint velocities according to the input JointIdMap (i.e.  More... | |
| bool | setJointVelocity (const JointNameMap &qdot) | 
| Sets the XBotInterface internal joint velocities according to the input JointNameMap (i.e.  More... | |
| bool | setMotorVelocity (const Eigen::VectorXd &qdot) | 
| Sets the XBotInterface internal motor velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setMotorVelocity (const JointIdMap &qdot) | 
| Sets the XBotInterface internal motor velocities according to the input JointIdMap (i.e.  More... | |
| bool | setMotorVelocity (const JointNameMap &qdot) | 
| Sets the XBotInterface internal motor velocities according to the input JointNameMap (i.e.  More... | |
| bool | setJointAcceleration (const Eigen::VectorXd &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointAcceleration (const JointIdMap &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the input JointIdMap (i.e.  More... | |
| bool | setJointAcceleration (const JointNameMap &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the input JointNameMap (i.e.  More... | |
| bool | setJointEffort (const Eigen::VectorXd &tau) | 
| Sets the XBotInterface internal joint efforts according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointEffort (const JointIdMap &tau) | 
| Sets the XBotInterface internal joint efforts according to the input JointIdMap (i.e.  More... | |
| bool | setJointEffort (const JointNameMap &tau) | 
| Sets the XBotInterface internal joint efforts according to the input JointNameMap (i.e.  More... | |
| bool | setStiffness (const Eigen::VectorXd &K) | 
| Sets the XBotInterface internal joint stiffness according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setStiffness (const JointIdMap &K) | 
| Sets the XBotInterface internal joint stiffness according to the input JointIdMap (i.e.  More... | |
| bool | setStiffness (const JointNameMap &K) | 
| Sets the XBotInterface internal joint stiffness according to the input JointNameMap (i.e.  More... | |
| bool | setDamping (const Eigen::VectorXd &D) | 
| Sets the XBotInterface internal joint damping according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setDamping (const JointIdMap &D) | 
| Sets the XBotInterface internal joint damping according to the input JointIdMap (i.e.  More... | |
| bool | setDamping (const JointNameMap &D) | 
| Sets the XBotInterface internal joint damping according to the input JointNameMap (i.e.  More... | |
|  Public Member Functions inherited from XBot::XBotInterface | |
| XBotInterface () | |
| XBotInterface (const XBotInterface &other) | |
| XBotInterface & | operator= (const XBotInterface &rhs) | 
| virtual | ~XBotInterface () | 
| bool | init (const std::string &path_to_cfg) | 
| bool | init (const ConfigOptions &options) | 
| const ConfigOptions & | getConfigOptions () const | 
| Gets the configuration struct that has been used to build the XBotInterface.  More... | |
| const std::string & | getPathToConfig () const | 
| Gets the path to the YAML config file used to build the XBotInterface.  More... | |
| const urdf::ModelInterface & | getUrdf () const | 
| Getter for the robot URDF model corresponding to the URDF xml file specified in the YAML config file.  More... | |
| const std::string & | getUrdfPath () const | 
| getUrdfPath Getter for the path to the URDF model  More... | |
| const srdf_advr::Model & | getSrdf () const | 
| Getter fot the robot SRDF model corresponding to the SRDF xml file specified in the YAML config file.  More... | |
| const std::string & | getSrdfPath () const | 
| getSrdfPath Getter for the path to the SRDF model  More... | |
| const std::string & | getUrdfString () const | 
| Returns the robot URDF xml as a string.  More... | |
| const std::string & | getSrdfString () const | 
| Returns the robot SRDF xml as a string.  More... | |
| bool | getRobotState (const std::string &state_name, Eigen::VectorXd &q) const | 
| Gets the robot joints group state configuration as specified in the robot SRDF.  More... | |
| bool | getRobotState (const std::string &state_name, JointIdMap &q) const | 
| Gets the robot joints group state configuration as specified in the robot SRDF.  More... | |
| bool | getRobotState (const std::string &state_name, JointNameMap &q) const | 
| Gets the robot joints group state configuration as specified in the robot SRDF.  More... | |
| std::vector< std::string > | getChainNames () const | 
| Return a vector of available chain names as strings.  More... | |
| bool | hasChain (const std::string &chain_name) const | 
| A method for determining if a chain with name "chain_name" is defined inside the interface.  More... | |
| int | legs () const | 
| Returns the number of legs defined inside the interface.  More... | |
| int | arms () const | 
| Returns the number of arms defined inside the interface.  More... | |
| const std::vector< std::string > & | getEnabledJointNames () const | 
| Returns a vector of enabled joint names.  More... | |
| const std::vector< int > & | getEnabledJointId () const | 
| Returns a vector of enabled joint IDs.  More... | |
| bool | hasJoint (const std::string &joint_name) const | 
| Checks that a joint with name "joint_name" is defined as an enabled joint inside the interface.  More... | |
| bool | hasJoint (int joint_id) const | 
| Checks that a joint with ID "joint_id" is defined as an enabled joint inside the interface.  More... | |
| int | getJointNum () const | 
| Getter for the number of enabled joints.  More... | |
| XBot::Joint::ConstPtr | getJointByName (const std::string &joint_name) const | 
| Gets the joint with name "joint_name" if it is defined as enabled.  More... | |
| XBot::Joint::ConstPtr | getJointByID (int joint_id) const | 
| Gets the joint with ID "joint_id" if it is defined as enabled.  More... | |
| XBot::Joint::ConstPtr | getJointByDofIndex (int idx) const | 
| Gets the joint with the required dof index.  More... | |
| int | getDofIndex (const std::string &joint_name) const | 
| Gets the Eigen ID of the joint with name "joint_name".  More... | |
| int | getDofIndex (int joint_id) const | 
| Gets the Eigen ID of the joint with ID "joint_id".  More... | |
| bool | getDofIndex (const std::string &chain_name, std::vector< int > &ids) const | 
| Gets dof indices of all joints inside chain "chain_name".  More... | |
| void | initLog (MatLogger2::Ptr logger, int buffer_size=-1, int interleave=1, std::string prefix="") | 
| Pre-allocates memory for logging the robot state to a mat file.  More... | |
| void | log (MatLogger2::Ptr logger, double timestamp, const std::string &prefix="") const | 
| Logs the current robot state.  More... | |
| std::map< std::string, ForceTorqueSensor::ConstPtr > | getForceTorque () const | 
| Getter for the force-torque sensor map pertaining to the whole robot.  More... | |
| ForceTorqueSensor::ConstPtr | getForceTorque (const std::string &parent_link_name) const | 
| Returns a force-torque sensor given its parent-link name.  More... | |
| ForceTorqueSensor::ConstPtr | getForceTorque (int ft_id) const | 
| Returns a force-torque sensor given its sensor ID.  More... | |
| std::map< std::string, ImuSensor::ConstPtr > | getImu () | 
| Getter for the IMU sensor map pertaining to the chain.  More... | |
| ImuSensor::ConstPtr | getImu (const std::string &parent_link_name) const | 
| Returns an IMU sensor given its parent-link name.  More... | |
| ImuSensor::ConstPtr | getImu (int imu_id) const | 
| Returns an IMU sensor given its sensor ID.  More... | |
| std::map< std::string, Hand::Ptr > | getHand () | 
| Getter for the hands map pertaining to the whole robot.  More... | |
| Hand::Ptr | getHand (int hand_id) const | 
| Returns a hand given its hand ID.  More... | |
| bool | eigenToMap (const Eigen::VectorXd &vector, JointNameMap &name_map) const | 
| Converts a state vector for the whole robot to its JointNameMap representation.  More... | |
| bool | eigenToMap (const Eigen::VectorXd &vector, JointIdMap &id_map) const | 
| Converts a state vector for the whole robot to its JointIdMap representation.  More... | |
| bool | mapToEigen (const JointNameMap &map, Eigen::VectorXd &vector) const | 
| Converts a state vector for an arbitrary subset of the robot state (specified as a JointNameMap) to its Eigen representation.  More... | |
| bool | mapToEigen (const JointIdMap &map, Eigen::VectorXd &vector) const | 
| Converts a state vector for an arbitrary subset of the robot state (specified as a JointIdMap) to its Eigen representation.  More... | |
| bool | getJointPosition (Eigen::VectorXd &q) const | 
| Gets the robot joint positions as an Eigen vector.  More... | |
| bool | getMotorPosition (Eigen::VectorXd &q) const | 
| Gets the robot motor positions as an Eigen vector.  More... | |
| bool | getJointVelocity (Eigen::VectorXd &qdot) const | 
| Gets the robot joint velocities as an Eigen vector.  More... | |
| bool | getMotorVelocity (Eigen::VectorXd &qdot) const | 
| Gets the robot motor velocities as an Eigen vector.  More... | |
| bool | getJointAcceleration (Eigen::VectorXd &qddot) const | 
| Gets the robot joint accelerations as an Eigen vector.  More... | |
| bool | getJointEffort (Eigen::VectorXd &tau) const | 
| Gets the robot joint efforts as an Eigen vector.  More... | |
| bool | getTemperature (Eigen::VectorXd &temp) const | 
| Gets the robot joint temperatures as an Eigen vector.  More... | |
| bool | getJointPosition (JointIdMap &q) const | 
| Gets the robot joint positions as a JointIdMap, i.e.  More... | |
| bool | getMotorPosition (JointIdMap &q) const | 
| Gets the robot motor positions as a JointIdMap, i.e.  More... | |
| bool | getJointVelocity (JointIdMap &qdot) const | 
| Gets the robot joint velocities as a JointIdMap, i.e.  More... | |
| bool | getMotorVelocity (JointIdMap &qdot) const | 
| Gets the robot motor velocities as a JointIdMap, i.e.  More... | |
| bool | getJointAcceleration (JointIdMap &qddot) const | 
| Gets the robot joint accelerations as a JointIdMap, i.e.  More... | |
| bool | getJointEffort (JointIdMap &tau) const | 
| Gets the robot joint efforts as a JointIdMap, i.e.  More... | |
| bool | getTemperature (JointIdMap &temp) const | 
| Gets the robot joint temperatures as a JointIdMap, i.e.  More... | |
| bool | getJointPosition (JointNameMap &q) const | 
| Gets the robot joint postions as a JointNameMap, i.e.  More... | |
| bool | getMotorPosition (JointNameMap &q) const | 
| Gets the robot motor postions as a JointNameMap, i.e.  More... | |
| bool | getJointVelocity (JointNameMap &qdot) const | 
| Gets the robot joint velocities as a JointNameMap, i.e.  More... | |
| bool | getMotorVelocity (JointNameMap &qdot) const | 
| Gets the robot motor velocities as a JointNameMap, i.e.  More... | |
| bool | getJointAcceleration (JointNameMap &qddot) const | 
| Gets the robot joint accelerations as a JointNameMap, i.e.  More... | |
| bool | getJointEffort (JointNameMap &tau) const | 
| Gets the robot joint efforts as a JointNameMap, i.e.  More... | |
| bool | getTemperature (JointNameMap &temp) const | 
| Gets the robot joint temperatures as a JointNameMap, i.e.  More... | |
| bool | setJointPosition (const Eigen::VectorXd &q) | 
| Sets the XBotInterface internal joint positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setMotorPosition (const Eigen::VectorXd &q) | 
| Sets the XBotInterface internal motor positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointVelocity (const Eigen::VectorXd &qdot) | 
| Sets the XBotInterface internal joint velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setMotorVelocity (const Eigen::VectorXd &qdot) | 
| Sets the XBotInterface internal motor velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointAcceleration (const Eigen::VectorXd &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointEffort (const Eigen::VectorXd &tau) | 
| Sets the XBotInterface internal joint efforts according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setTemperature (const Eigen::VectorXd &temp) | 
| Sets the XBotInterface internal joint temperatures according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setJointPosition (const JointIdMap &q) | 
| Sets the XBotInterface internal joint positions according to the input JointIdMap (i.e.  More... | |
| bool | setMotorPosition (const JointIdMap &q) | 
| Sets the XBotInterface internal motor positions according to the input JointIdMap (i.e.  More... | |
| bool | setJointVelocity (const JointIdMap &qdot) | 
| Sets the XBotInterface internal joint velocities according to the input JointIdMap (i.e.  More... | |
| bool | setMotorVelocity (const JointIdMap &qdot) | 
| Sets the XBotInterface internal motor velocities according to the input JointIdMap (i.e.  More... | |
| bool | setJointAcceleration (const JointIdMap &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the input JointIdMap (i.e.  More... | |
| bool | setJointEffort (const JointIdMap &tau) | 
| Sets the XBotInterface internal joint efforts according to the input JointIdMap (i.e.  More... | |
| bool | setTemperature (const JointIdMap &temp) | 
| Sets the XBotInterface internal motor temperatures according to the input JointIdMap (i.e.  More... | |
| bool | setJointPosition (const JointNameMap &q) | 
| Sets the XBotInterface internal joint positions according to the input JointNameMap (i.e.  More... | |
| bool | setMotorPosition (const JointNameMap &q) | 
| Sets the XBotInterface internal motor positions according to the input JointNameMap (i.e.  More... | |
| bool | setJointVelocity (const JointNameMap &qdot) | 
| Sets the XBotInterface internal joint velocities according to the input JointNameMap (i.e.  More... | |
| bool | setMotorVelocity (const JointNameMap &qdot) | 
| Sets the XBotInterface internal motor velocities according to the input JointNameMap (i.e.  More... | |
| bool | setJointAcceleration (const JointNameMap &qddot) | 
| Sets the XBotInterface internal joint accelerations according to the input JointNameMap (i.e.  More... | |
| bool | setJointEffort (const JointNameMap &tau) | 
| Sets the XBotInterface internal joint efforts according to the input JointNameMap (i.e.  More... | |
| bool | setTemperature (const JointNameMap &temp) | 
| Sets the XBotInterface internal joint temperatures according to the input JointNameMap (i.e.  More... | |
| bool | getPositionReference (Eigen::VectorXd &q) const | 
| Gets the robot position references as an Eigen vector.  More... | |
| bool | getVelocityReference (Eigen::VectorXd &qdot) const | 
| Gets the robot velocity references as an Eigen vector.  More... | |
| bool | getEffortReference (Eigen::VectorXd &tau) const | 
| Gets the robot effort references as an Eigen vector.  More... | |
| bool | getStiffness (Eigen::VectorXd &K) const | 
| Gets the robot stiffness as an Eigen vector.  More... | |
| bool | getDamping (Eigen::VectorXd &D) const | 
| Gets the robot damping as an Eigen vector.  More... | |
| bool | getPositionReference (JointIdMap &q) const | 
| Gets the robot position references as a JointIdMap, i.e.  More... | |
| bool | getVelocityReference (JointIdMap &qdot) const | 
| Gets the robot velocity references as a JointIdMap, i.e.  More... | |
| bool | getEffortReference (JointIdMap &tau) const | 
| Gets the robot effort references as a JointIdMap, i.e.  More... | |
| bool | getStiffness (JointIdMap &K) const | 
| Gets the robot stiffness as a JointIdMap, i.e.  More... | |
| bool | getDamping (JointIdMap &D) const | 
| Gets the robot damping as a JointIdMap, i.e.  More... | |
| bool | getPositionReference (JointNameMap &q) const | 
| Gets the robot postion references as a JointNameMap, i.e.  More... | |
| bool | getVelocityReference (JointNameMap &qdot) const | 
| Gets the robot velocity references as a JointNameMap, i.e.  More... | |
| bool | getEffortReference (JointNameMap &tau) const | 
| Gets the robot effort references as a JointNameMap, i.e.  More... | |
| bool | getStiffness (JointNameMap &K) const | 
| Gets the robot stiffness as a JointNameMap, i.e.  More... | |
| bool | getDamping (JointNameMap &D) const | 
| Gets the robot damping as a JointNameMap, i.e.  More... | |
| bool | setPositionReference (const Eigen::VectorXd &q) | 
| Sets the XBotInterface internal joint position references according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setVelocityReference (const Eigen::VectorXd &qdot) | 
| Sets the XBotInterface internal joint velocity references according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setEffortReference (const Eigen::VectorXd &tau) | 
| Sets the XBotInterface internal joint effort references according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setStiffness (const Eigen::VectorXd &K) | 
| Sets the XBotInterface internal joint stiffness according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setDamping (const Eigen::VectorXd &D) | 
| Sets the XBotInterface internal joint damping according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.  More... | |
| bool | setPositionReference (const JointIdMap &q) | 
| Sets the XBotInterface internal joint position references according to the input JointIdMap (i.e.  More... | |
| bool | setVelocityReference (const JointIdMap &qdot) | 
| Sets the XBotInterface internal joint velocity references according to the input JointIdMap (i.e.  More... | |
| bool | setEffortReference (const JointIdMap &tau) | 
| Sets the XBotInterface internal joint effort references according to the input JointIdMap (i.e.  More... | |
| bool | setStiffness (const JointIdMap &K) | 
| Sets the XBotInterface internal joint stiffness according to the input JointIdMap (i.e.  More... | |
| bool | setDamping (const JointIdMap &D) | 
| Sets the XBotInterface internal joint damping according to the input JointIdMap (i.e.  More... | |
| bool | setPositionReference (const JointNameMap &q) | 
| Sets the XBotInterface internal joint position references according to the input JointNameMap (i.e.  More... | |
| bool | setVelocityReference (const JointNameMap &qdot) | 
| Sets the XBotInterface internal joint velocity references according to the input JointNameMap (i.e.  More... | |
| bool | setEffortReference (const JointNameMap &tau) | 
| Sets the XBotInterface internal joint effort references according to the input JointNameMap (i.e.  More... | |
| bool | setStiffness (const JointNameMap &K) | 
| Sets the XBotInterface internal joint stiffness according to the input JointNameMap (i.e.  More... | |
| bool | setDamping (const JointNameMap &D) | 
| Sets the XBotInterface internal joint damping according to the input JointNameMap (i.e.  More... | |
| void | getJointLimits (Eigen::VectorXd &q_min, Eigen::VectorXd &q_max) const | 
| Gets a vector of the robot joint limits, as specified in the URDF file.  More... | |
| void | getVelocityLimits (Eigen::VectorXd &qdot_max) const | 
| Gets a vector of the robot joint velocity limits, as specified in the URDF file.  More... | |
| void | getEffortLimits (Eigen::VectorXd &tau_max) const | 
| Gets a vector of the robot joint effort limits, as specified in the URDF file.  More... | |
| bool | checkJointLimits (const Eigen::VectorXd &q, std::vector< std::string > &violating_joints) const | 
| Check the input joint position vector against joint limits.  More... | |
| bool | checkVelocityLimits (const Eigen::VectorXd &qdot, std::vector< std::string > &violating_joints) const | 
| Check the input joint velocity vector against joint limits.  More... | |
| bool | checkEffortLimits (const Eigen::VectorXd &tau, std::vector< std::string > &violating_joints) const | 
| Check the input joint effort vector against joint limits.  More... | |
| bool | checkJointLimits (const Eigen::VectorXd &q) const | 
| Check the input joint position vector against joint limits.  More... | |
| bool | checkVelocityLimits (const Eigen::VectorXd &qdot) const | 
| Check the input joint velocity vector against joint limits.  More... | |
| bool | checkEffortLimits (const Eigen::VectorXd &tau) const | 
| Check the input joint effort vector against joint limits.  More... | |
| bool | enforceJointLimits (JointIdMap &q) const | 
| Modifies the input joint position map by enforcing joint limits.  More... | |
| bool | enforceJointLimits (JointNameMap &q) const | 
| Modifies the input joint position map by enforcing joint limits.  More... | |
| bool | enforceJointLimits (Eigen::VectorXd &q) const | 
| Modifies the input joint position vector by enforcing joint limits.  More... | |
| bool | enforceEffortLimit (Eigen::VectorXd &tau) const | 
| Modifies the input joint effort vector by enforcing effort limits.  More... | |
| bool | enforceVelocityLimit (Eigen::VectorXd &qdot) const | 
| Modifies the input joint velcoity vector by enforcing joint limits.  More... | |
| template<typename... SyncFlags> | |
| bool | sync (const XBotInterface &other, SyncFlags... flags) | 
| Synchronize the current XBotInterface with another XBotInterface object: only the common chains will be taken into account.  More... | |
| const std::map< std::string, XBot::KinematicChain::Ptr > & | getChainMap () const | 
| Getter for the chain map inside the XBotInterface.  More... | |
| void | print () const | 
| Print a pretty table about the robot state.  More... | |
| void | printTracking () const | 
| Print a pretty table about the robot tracking.  More... | |
| Static Public Member Functions | |
| static ModelInterface::Ptr | getModel (const ConfigOptions &config) | 
| Factory method for generating instances of the ModelInterface class according to the provided configuration file, which specifies the URDF/SRDF to be used, as well as the specific implementation of ModelInterface to be loaded.  More... | |
| static ModelInterface::Ptr | getModel (const std::string &path_to_cfg, AnyMapConstPtr any_map=AnyMapConstPtr()) | 
| Factory method for generating instances of the ModelInterface class according to the provided configuration file, which specifies the URDF/SRDF to be used, as well as the specific implementation of ModelInterface to be loaded.  More... | |
| Protected Member Functions | |
| virtual bool | init_internal (const ConfigOptions &config) | 
| virtual bool | init_model (const ConfigOptions &config)=0 | 
| virtual bool | update_internal (bool update_position, bool update_velocity, bool update_desired_acceleration)=0 | 
| void | rotationEigenToKDL (const Eigen::Matrix3d &eigen_rotation, KDL::Rotation &kdl_rotation) const | 
| void | rotationKDLToEigen (const KDL::Rotation &kdl_rotation, Eigen::Matrix3d &eigen_rotation) const | 
|  Protected Member Functions inherited from XBot::XBotInterface | |
| Joint::Ptr | getJointByNameInternal (const std::string &joint_name) const | 
| Joint::Ptr | getJointByIdInternal (int joint_id) const | 
| Joint::Ptr | getJointByDofIndexInternal (int dof_index) const | 
| const std::map< std::string, ForceTorqueSensor::Ptr > & | getForceTorqueInternal () const | 
| const std::map< std::string, ImuSensor::Ptr > & | getImuInternal () const | 
| virtual bool | post_init () | 
| const std::vector< std::string > & | getModelOrderedChainName () const | 
| Protected Attributes | |
| bool | _is_floating_base | 
|  Protected Attributes inherited from XBot::XBotInterface | |
| XBotCoreModel | _XBotModel | 
| std::map< std::string, XBot::KinematicChain::Ptr > | _chain_map | 
| std::vector< Joint::Ptr > | _ordered_joint_vector | 
| std::vector< Joint::Ptr > | _joint_vector | 
| std::map< std::string, ForceTorqueSensor::Ptr > | _ft_map | 
| std::map< int, ForceTorqueSensor::Ptr > | _ft_id_map | 
| std::map< std::string, ImuSensor::Ptr > | _imu_map | 
| std::map< int, ImuSensor::Ptr > | _imu_id_map | 
| std::map< std::string, Hand::Ptr > | _hand_map | 
| std::map< int, Hand::Ptr > | _hand_id_map | 
| std::vector< std::string > | _ordered_chain_names | 
| std::map< int, int > | _joint_id_to_eigen_id | 
| std::map< std::string, int > | _joint_name_to_eigen_id | 
ModelInterface is an abstraction layer for a kinematic/dynamic model of a robot.
It inherits from the XBotInterface class the organization of a robot as a collection of kinematic chains.
| typedef std::shared_ptr<const ModelInterface> XBot::ModelInterface::ConstPtr | 
Shared pointer to const ModelInterface.
| typedef std::shared_ptr<ModelInterface> XBot::ModelInterface::Ptr | 
Shared pointer to a ModelInterface.
| 
 | default | 
| 
 | delete | 
| XBot::ModelChain & XBot::ModelInterface::arm | ( | int | arm_id | ) | 
Returns a handle to the kinematic chain corresponding to the arm n° arm_id.
The order of arms is defined in the SRDF file which was provided to ModelInterface::getModel(). If the requested chain is not defined, a dummy chain is returned and an error is displayed.
| arm_id | The requested arm id, from 0 to arms()-1 | 
| const XBot::ModelChain & XBot::ModelInterface::arm | ( | int | arm_id | ) | const | 
| XBot::ModelChain & XBot::ModelInterface::chain | ( | const std::string & | chain_name | ) | 
Returns a handle to the kinematic chain named chain_name.
If such a chain is not defined, a dummy chain is returned and an error is displayed.
| chain_name | The name of the requested chain | 
| const XBot::ModelChain & XBot::ModelInterface::chain | ( | const std::string & | chain_name | ) | const | 
| bool XBot::ModelInterface::computeConstrainedInverseDynamics | ( | const Eigen::MatrixXd & | J, | 
| const Eigen::VectorXd & | weights, | ||
| Eigen::VectorXd & | tau | ||
| ) | const | 
Computes inverse dynamics for a constrained system.
| J | The constraint jacobian | 
| weights | Torque weights for weighted least-squares computation (only matters if system is floating-base) | 
| tau | The resultind ID torque vector | 
| 
 | pure virtual | 
Computes gravity compensation torques.
Make sure that you correctly specified the gravity vector in order to obtain correct results.
| g | The gravity compensation torque vector (if model is floating base, includes virtual joints effort). | 
| 
 | pure virtual | 
Computes inverse dynamics.
| tau | The inverse dynamics torque vector (if model is floating base, includes virtual joints effort). | 
| bool XBot::ModelInterface::computeJdotQdot | ( | const std::string & | link_name, | 
| const Eigen::Vector3d & | point, | ||
| Eigen::Vector6d & | jdotqdot | ||
| ) | const | 
Computed the product of the link_name jacobian time derivative by the joint velocity vector.
The reference point of the jacobian is provided as the argument "point".
| link_name | The link name | 
| point | A point in link_name coordinates- | 
| jdotqdot | The resulting acceleration twist. | 
| 
 | virtual | 
Computed the product of the link_name jacobian time derivative by the joint velocity vector.
The reference point of the jacobian is provided as the argument "point".
| link_name | The link name | 
| point | A point in link_name coordinates- | 
| jdotqdot | The resulting acceleration twist. | 
| 
 | pure virtual | 
Computes the non-linear torque term without the contribution from gravity, i.e.
the sum of centrifugal/coriolis torques.
| n | The non-linear torques vector (if model is floating base, includes virtual joints effort). | 
| bool XBot::ModelInterface::computeRelativeJdotQdot | ( | const std::string & | target_link_name, | 
| const std::string & | base_link_name, | ||
| Eigen::Vector6d & | jdotqdot | ||
| ) | const | 
computeRelativeJdotQdot return the relative acceleration component between "target_link" and "base_link", given by JdotQdot, expressed in "base_link"
| target_link_name | |
| base_link_name | |
| jdotqdot | 
| 
 | pure virtual | 
computeRelativeJdotQdot return the relative acceleration component between "target_link" and "base_link", given by JdotQdot, expressed in "base_link"
| target_link_name | |
| base_link_name | |
| jdotqdot | 
| bool XBot::ModelInterface::getAccelerationTwist | ( | const std::string & | link_name, | 
| Eigen::Vector6d & | acceleration | ||
| ) | const | 
Gets the acceleration twist of link_name (first linear, then angular acceleration).
The reference point of the acceleration twist is the origin of the link itself.
| link_name | The link name | 
| velocity | The acceleration twist of the link "link_name" | 
| 
 | pure virtual | 
Gets the acceleration twist of link_name (first linear, then angular acceleration).
The reference point of the acceleration twist is the origin of the link itself.
| link_name | The link name | 
| velocity | The acceleration twist of the link "link_name" | 
| int XBot::ModelInterface::getActuatedJointNum | ( | ) | const | 
Gets the number of actuated joints in the model, i.e.
possible virtual joints (floating base models) are not working.
| 
 | pure virtual | 
Gets the robot centroidal momentum matrix, i.e.
the jacobian of the centroidal momentum.
| centroidal_momentum | The robot centroidal momentum. The first three rows represent the robot linear momentum, while the last three rows contain the angular momentum about the COM, | 
| 
 | virtual | 
Gets the robot mometum about its COM.
| centroidal_momentum_matrix | The robot centroidal momentum matrix. The first three rows represent the jacobian of the robot linear momentum, while the last three rows contain the angular momentum about the COM, | 
| 
 | virtual | 
Gets the robot centroidal momentum matrix, i.e.
the jacobian of the centroidal momentum.
| centroidal_momentum_matrix | The robot centroidal momentum matrix. The first three rows represent the jacobian of the robot linear momentum, while the last three rows contain the angular momentum about the COM, | 
| CMMdotQdot | The d(CMM)/dt * qdot term, i.e. the derivative of the centroidal momentum due to joint velocities. | 
| bool XBot::ModelInterface::getChainSelectionMatrix | ( | const std::string & | chain_name, | 
| Eigen::MatrixXd & | S | ||
| ) | const | 
Gets a selection matrix for the requested chain, i.e.
a matrix S such that the product of S by the configuration vector returns the sub-vector pertaining to the specified chain.
| chain_name | The chain name. | 
| S | The requested selection matrix. | 
| bool XBot::ModelInterface::getCOM | ( | const std::string & | reference_frame, | 
| Eigen::Vector3d & | com_position | ||
| ) | const | 
Gets the COM position vector w.r.t.
the reference_frame
| reference_frame | The link name w.r.t. which the COM position will be expressed | 
| com_position | The center of mass position vector w.r.t. the reference_frame | 
| bool XBot::ModelInterface::getCOM | ( | const std::string & | reference_frame, | 
| KDL::Vector & | com_position | ||
| ) | const | 
Gets the COM position vector w.r.t.
the reference_frame
| reference_frame | The link name w.r.t. which the COM position will be expressed | 
| com_position | The center of mass position vector w.r.t. the reference_frame | 
| void XBot::ModelInterface::getCOM | ( | Eigen::Vector3d & | com_position | ) | const | 
Gets the COM position vector w.r.t.
the world frame
| com_position | The center of mass position vector w.r.t. the world frame | 
| 
 | pure virtual | 
Gets the COM position vector w.r.t.
the world frame
| com_position | The center of mass position vector w.r.t. the world frame | 
| void XBot::ModelInterface::getCOMAcceleration | ( | Eigen::Vector3d & | acceleration | ) | const | 
Gets the COM acceleration expressed in the world frame.
| velocity | The COM acceleration expressed in the world frame | 
| 
 | pure virtual | 
Gets the COM acceleration expressed in the world frame.
| velocity | The COM acceleration expressed in the world frame | 
| void XBot::ModelInterface::getCOMJacobian | ( | Eigen::MatrixXd & | J | ) | const | 
Gets the COM Jacobian expressed in the world frame.
| J | The COM Jacobian expressed in the world frame. Note that, since the COM is not fixed to any link, the Jacobian orientation part (i.e. the lower three rows) are undefined and filled with zeros. | 
| 
 | virtual | 
Gets the COM Jacobian expressed in the world frame and the d(Jcom)/dt * qdot term, i.e.
the COM acceleration due to joint velocities.
| J | The COM Jacobian expressed in the world frame. Note that, since the COM is not fixed to any link, the Jacobian orientation part (i.e. the lower three rows) are undefined and filled with zeros. | 
| dJcomqdot | The d(Jcom)/dt * qdot term, i.e. the COM acceleration due to joint velocities. | 
| 
 | virtual | 
Gets the COM Jacobian expressed in the world frame.
| J | The COM Jacobian expressed in the world frame. Note that, since the COM is not fixed to any link, the Jacobian orientation part (i.e. the lower three rows) are undefined and filled with zeros. | 
| 
 | virtual | 
Gets the COM Jacobian expressed in the world frame and the d(Jcom)/dt * qdot term, i.e.
the COM acceleration due to joint velocities.
| J | The COM Jacobian expressed in the world frame. Note that, since the COM is not fixed to any link, the Jacobian orientation part (i.e. the lower three rows) are undefined and filled with zeros. | 
| dJcomqdot | The d(Jcom)/dt * qdot term, i.e. the COM acceleration due to joint velocities. | 
| void XBot::ModelInterface::getCOMVelocity | ( | Eigen::Vector3d & | velocity | ) | const | 
Gets the COM velocity expressed in the world frame.
| velocity | The COM velocity expressed in the world frame | 
| 
 | pure virtual | 
Gets the COM velocity expressed in the world frame.
| velocity | The COM velocity expressed in the world frame | 
| bool XBot::XBotInterface::getDamping | 
Gets the robot damping as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| D | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getDamping | 
Gets the robot damping as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| D | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getDamping | 
Gets the robot damping as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| D | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| 
 | pure virtual | 
Gets the name of the floating base link.
| floating_base_link | The name of the floating base link | 
| bool XBot::ModelInterface::getFloatingBasePose | ( | Eigen::Affine3d & | floating_base_pose | ) | const | 
Gets the floating base pose w.r.t.
the world frame
| floating_base_pose | The homogeneous transformation which transforms a point from floating base frame to world frame | 
| bool XBot::ModelInterface::getFloatingBasePose | ( | KDL::Frame & | floating_base_pose | ) | const | 
Gets the floating base pose w.r.t.
the world frame.
| floating_base_pose | The homogeneous transformation which transforms a point from floating base frame to world frame | 
| bool XBot::ModelInterface::getFloatingBaseTwist | ( | Eigen::Vector6d & | floating_base_twist | ) | const | 
Gets the floating base twist w.r.t.
the world frame
| floating_base_twist | The twist of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::getFloatingBaseTwist | ( | KDL::Twist & | floating_base_twist | ) | const | 
Gets the floating base twist w.r.t.
the world frame
| floating_base_twist | The twist of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::getGravity | ( | const std::string & | reference_frame, | 
| Eigen::Vector3d & | gravity | ||
| ) | const | 
Gets the gravity vector expressed in the reference_frame.
| reference_frame | The link name w.r.t. which the gravity vector will be expressed | 
| gravity | The gravity vector expressed in the world frame | 
| bool XBot::ModelInterface::getGravity | ( | const std::string & | reference_frame, | 
| KDL::Vector & | gravity | ||
| ) | const | 
Gets the gravity vector expressed in the reference_frame.
| reference_frame | The link name w.r.t. which the gravity vector will be expressed | 
| gravity | The gravity vector expressed in the world frame | 
| void XBot::ModelInterface::getGravity | ( | Eigen::Vector3d & | gravity | ) | const | 
Gets the gravity vector expressed in the world frame.
| gravity | The gravity vector expressed in the world frame. | 
| 
 | pure virtual | 
Gets the gravity vector expressed in the world frame.
| gravity | The gravity vector expressed in the world frame. | 
| 
 | virtual | 
getInertiaInverse compute the inverse of the Inertia Matrix
| Minv | the inverse of the inertia matrix | 
| 
 | virtual | 
getInertiaInverseTimesMatrix Computes the inverse of the Inertia Matrix times a given matrix
| Mat | input matrix | 
| Minv_Mat | the resultant matrix | 
| 
 | virtual | 
getInertiaInverseTimesVector Computes the inverse of the Inertia Matrix times a given vector
| vec | input vector | 
| minv_vec | the resultant vector | 
| 
 | pure virtual | 
Gets the joint space inertia matrix of the robot.
| M | The requested inertia matrix. | 
| bool XBot::ModelInterface::getJacobian | ( | const std::string & | link_name, | 
| const Eigen::Vector3d & | reference_point, | ||
| Eigen::MatrixXd & | J | ||
| ) | const | 
Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.
first linear then angular velocity). The reference point of the Jacobian is the reference_point arg.
| link_name | The link name | 
| reference_point | The reference point w.r.t. which the jacobian is computed | 
| J | The Jacobian expressed in the world frame | 
| 
 | pure virtual | 
Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.
first linear then angular velocity). The reference point of the Jacobian is the reference_point arg.
| link_name | The link name | 
| reference_point | The reference point w.r.t. which the jacobian is computed | 
| J | The Jacobian expressed in the world frame | 
| bool XBot::ModelInterface::getJacobian | ( | const std::string & | link_name, | 
| const std::string & | target_frame, | ||
| Eigen::MatrixXd & | J | ||
| ) | const | 
Gets the Jacobian of link_name expressed in the target_frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name according to target_frame (i.e.
first linear then angular velocity). The reference point is the origin of the link with link_name name.
| link_name | The link name | 
| target_frame | The target frame name | 
| J | The Jacobian expressed in the world frame | 
| bool XBot::ModelInterface::getJacobian | ( | const std::string & | link_name, | 
| const std::string & | target_frame, | ||
| KDL::Jacobian & | J | ||
| ) | const | 
Gets the Jacobian of link_name expressed in the target_frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name according to target_frame (i.e.
first linear then angular velocity). The reference point is the origin of the link with link_name name.
| link_name | The link name | 
| target_frame | The target frame name | 
| J | The Jacobian expressed in the world frame | 
| bool XBot::ModelInterface::getJacobian | ( | const std::string & | link_name, | 
| Eigen::MatrixXd & | J | ||
| ) | const | 
Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.
first linear then angular velocity). The reference point is the origin of the link with link_name name.
| link_name | The link name | 
| J | The Jacobian expressed in the world frame | 
| bool XBot::ModelInterface::getJacobian | ( | const std::string & | link_name, | 
| KDL::Jacobian & | J | ||
| ) | const | 
Gets the Jacobian of link_name expressed in the world frame, i.e a matrix such that its product with the derivative of the configuration vector gives the velocity twist of link_name (i.e.
first linear then angular velocity). The reference point is the origin of the link with link_name name.
| link_name | The link name | 
| J | The Jacobian expressed in the world frame | 
| bool XBot::XBotInterface::getJointAcceleration | 
Gets the robot joint accelerations as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| qddot | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getJointAcceleration | 
Gets the robot joint accelerations as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| qddot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointAcceleration | 
Gets the robot joint accelerations as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| qddot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointEffort | 
Gets the robot joint efforts as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| tau | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getJointEffort | 
Gets the robot joint efforts as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| tau | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointEffort | 
Gets the robot joint efforts as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| tau | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointPosition | 
Gets the robot joint positions as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| q | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getJointPosition | 
Gets the robot joint positions as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| q | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointPosition | 
Gets the robot joint postions as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| q | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::ModelInterface::getJointSelectionMatrix | ( | const std::string & | joint_name, | 
| Eigen::RowVectorXd & | S | ||
| ) | const | 
Gets a selection matrix for the requested joint, i.e.
a matrix S such that the product of S by the configuration vector returns the value pertaining to the specified joint.
| joint_name | The chain name. | 
| S | The requested selection matrix. | 
| bool XBot::ModelInterface::getJointSelectionMatrix | ( | int | joint_id, | 
| Eigen::RowVectorXd & | S | ||
| ) | const | 
Gets a selection matrix for the requested joint, i.e.
a matrix S such that the product of S by the configuration vector returns the value pertaining to the specified joint.
| joint_id | The chain ID. | 
| S | The requested selection matrix. | 
| bool XBot::XBotInterface::getJointVelocity | 
Gets the robot joint velocities as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| qdot | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getJointVelocity | 
Gets the robot joint velocities as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| qdot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getJointVelocity | 
Gets the robot joint velocities as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| qdot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| 
 | pure virtual | 
getLinkID return the link ID
| link_name | the name fo the link | 
| 
 | pure virtual | 
Gets the weight of the robot.
| 
 | static | 
Factory method for generating instances of the ModelInterface class according to the provided configuration file, which specifies the URDF/SRDF to be used, as well as the specific implementation of ModelInterface to be loaded.
| path_to_cfg | Path to the YAML configuration file. | 
| any_map | a map with objects needed by RobotInterface actual implementations | 
| 
 | static | 
Factory method for generating instances of the ModelInterface class according to the provided configuration file, which specifies the URDF/SRDF to be used, as well as the specific implementation of ModelInterface to be loaded.
| path_to_cfg | Path to the YAML configuration file. | 
| any_map | a map with objects needed by RobotInterface actual implementations | 
| 
 | pure virtual | 
Gets a vector with the joint names ordered according to the model.
If the model is floating-base, the first six names are the virtual joint names.
| joint_name | The joint names ordered according to the model. | 
| bool XBot::XBotInterface::getMotorPosition | 
Gets the robot motor positions as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| q | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getMotorPosition | 
Gets the robot motor positions as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| q | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getMotorPosition | 
Gets the robot motor postions as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| q | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getMotorVelocity | 
Gets the robot motor velocities as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| qdot | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getMotorVelocity | 
Gets the robot motor velocities as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| qdot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getMotorVelocity | 
Gets the robot motor velocities as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| qdot | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::ModelInterface::getOrientation | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| Eigen::Matrix3d & | orientation | ||
| ) | const | 
Computes the orientation of the source_frame w.r.t.
the target_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| orientation | A rotation matrix which rotates a vector from source frame to target frame v_target = R * v_source | 
| bool XBot::ModelInterface::getOrientation | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| KDL::Rotation & | orientation | ||
| ) | const | 
Computes the orientation of the target_frame w.r.t.
the source_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| orientation | A rotation matrix which rotates a vector from source frame to target frame v_target = R * v_source | 
| bool XBot::ModelInterface::getOrientation | ( | const std::string & | source_frame, | 
| Eigen::Matrix3d & | orientation | ||
| ) | const | 
Computes the orientation of the source_frame w.r.t.
the world frame
| source_frame | The source link name. | 
| orientation | A rotation matrix which rotates a vector from source frame to world frame v_world = R * v_source | 
| bool XBot::ModelInterface::getOrientation | ( | const std::string & | source_frame, | 
| KDL::Rotation & | orientation | ||
| ) | const | 
Computes the orientation of the source_frame w.r.t.
the world frame
| source_frame | The source link name. | 
| orientation | A rotation matrix which rotates a vector from source frame to world frame v_world = R * v_source | 
| bool XBot::ModelInterface::getPointAcceleration | ( | const std::string & | link_name, | 
| const Eigen::Vector3d & | point, | ||
| Eigen::Vector3d & | acceleration | ||
| ) | const | 
Gets the acceleration of a given point which is solidal with the given link.
| link_name | The link which point is attached to. | 
| point | A point in link frame coordinates. | 
| acceleration | The acceleration of point. | 
| 
 | pure virtual | 
Gets the acceleration of a given point which is solidal with the given link.
| link_name | The link which point is attached to. | 
| point | A point in link frame coordinates. | 
| acceleration | The acceleration of point. | 
| bool XBot::ModelInterface::getPointPosition | ( | const std::string & | source_frame, | 
| const Eigen::Vector3d & | source_point, | ||
| Eigen::Vector3d & | world_point | ||
| ) | const | 
Gets the position in world coordinates for a source_point expressed w.r.t.
a source_frame.
| source_frame | The frame according to which source_point is expressed. | 
| source_point | The source_point in source-frame coordinates. | 
| world_point | The requested point in world coordinates. | 
| bool XBot::ModelInterface::getPointPosition | ( | const std::string & | source_frame, | 
| const KDL::Vector & | source_point, | ||
| KDL::Vector & | world_point | ||
| ) | const | 
Gets the position in world coordinates for a source_point expressed w.r.t.
a source_frame.
| source_frame | The frame according to which source_point is expressed. | 
| source_point | The source_point in source-frame coordinates. | 
| world_point | The requested point in world coordinates. | 
| bool XBot::ModelInterface::getPointPosition | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| const Eigen::Vector3d & | source_point, | ||
| Eigen::Vector3d & | target_point | ||
| ) | const | 
Gets the position in target_frame coordinates for a source_point expressed w.r.t.
source_frame.
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| source_point | The source_point in world coordinates. | 
| target_point | The requested point in target_frame coordinates. | 
| bool XBot::ModelInterface::getPointPosition | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| const KDL::Vector & | source_point, | ||
| KDL::Vector & | target_point | ||
| ) | const | 
Gets the position in target_frame coordinates for a source_point expressed w.r.t.
source_frame.
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| source_point | The source_point in world coordinates. | 
| target_point | The requested point in target_frame coordinates. | 
| bool XBot::ModelInterface::getPose | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| Eigen::Affine3d & | pose | ||
| ) | const | 
Computes the pose of the source_frame w.r.t.
the target_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| pose | A homogeneous transformation which transforms a point from source frame to target frame P_target = T * P_source | 
| bool XBot::ModelInterface::getPose | ( | const std::string & | source_frame, | 
| const std::string & | target_frame, | ||
| KDL::Frame & | pose | ||
| ) | const | 
Computes the pose of the source_frame w.r.t.
the target_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| pose | A homogeneous transformation which transforms a point from source frame to target frame P_target = T * P_source | 
| bool XBot::ModelInterface::getPose | ( | const std::string & | source_frame, | 
| Eigen::Affine3d & | pose | ||
| ) | const | 
Computes the pose of the source_frame w.r.t.
the world frame
| source_frame | The source link name. | 
| pose | A homogeneous transformation which transforms a point from source frame to world frame P_world = T * P_source | 
| 
 | pure virtual | 
Computes the pose of the source_frame w.r.t.
the world frame
| source_frame | The source link name. | 
| pose | A homogeneous transformation which transforms a point from source frame to world frame P_world = T * P_source | 
| void XBot::ModelInterface::getPosturalJacobian | ( | Eigen::MatrixXd & | J | ) | const | 
Gets the Jacacobian matrix corresponding to a joint-space postural task, i.e.
the identity matrix if the robot is fixed-base and a selection matrix for actuated joints if the robot is floating-base
| J | The postural jacobian | 
| bool XBot::ModelInterface::getRelativeAccelerationTwist | ( | const std::string & | link_name, | 
| const std::string & | base_link_name, | ||
| Eigen::Vector6d & | acceleration | ||
| ) | const | 
getRelativeAccelerationTwist compute the relative acceleration of body "link" wrt body "base_link" expressed in frame "base_link"
| link_name | |
| base_link_name | |
| acceleration | relative acceleration | 
| 
 | pure virtual | 
getRelativeAccelerationTwist compute the relative acceleration of body "link" wrt body "base_link" expressed in frame "base_link"
| link_name | |
| base_link_name | |
| acceleration | relative acceleration | 
| bool XBot::ModelInterface::getRelativeJacobian | ( | const std::string & | target_link_name, | 
| const std::string & | base_link_name, | ||
| Eigen::MatrixXd & | J | ||
| ) | const | 
Gets the relative Jacobian of target_link_name w.r.t to base_link_name.
The result is represented in the reference frame of base_link_name.
| target_link_name | The name of the target link | 
| base_link_name | The name of the base link | 
| J | The requested jacobian. | 
| 
 | virtual | 
Gets the relative Jacobian of target_link_name w.r.t to base_link_name.
The result is represented in the reference frame of base_link_name.
| target_link_name | The name of the target link | 
| base_link_name | The name of the base link | 
| J | The requested jacobian. | 
| bool XBot::ModelInterface::getRelativeVelocityTwist | ( | const std::string & | link_name, | 
| const std::string & | base_link_name, | ||
| Eigen::Vector6d & | velocity | ||
| ) | const | 
Gets the velocity twist of link_name (first linear, then angular velocity) w.r.t.
a user-specified base-link. The reference point of the velocity twist is the origin of the link itself.
| link_name | The link for which the twist is computed | 
| base_link_name | The base link for the computed velocity | 
| velocity | The twist of the link "link_name" w.r.t. "base_link_name" | 
| bool XBot::ModelInterface::getRelativeVelocityTwist | ( | const std::string & | link_name, | 
| const std::string & | base_link_name, | ||
| KDL::Twist & | velocity | ||
| ) | const | 
Gets the velocity twist of link_name (first linear, then angular velocity) w.r.t.
a user-specified base-link. The reference point of the velocity twist is the origin of the link itself.
| link_name | The link for which the twist is computed | 
| base_link_name | The base link for the computed velocity | 
| velocity | The twist of the link "link_name" w.r.t. "base_link_name" | 
| bool XBot::XBotInterface::getStiffness | 
Gets the robot stiffness as an Eigen vector.
The joint order inside the vector can be queried by calling the getEnabledJointNames/getEnabledJointId methods.
| K | A reference to an Eigen vector to be filled with the requested joint state. If the provided vector has wrong size it is resized automatically. | 
| bool XBot::XBotInterface::getStiffness | 
Gets the robot stiffness as a JointIdMap, i.e.
a map whose key represents the joint ID and whose value represents the required joint state.
| K | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::XBotInterface::getStiffness | 
Gets the robot stiffness as a JointNameMap, i.e.
a map whose key represents the joint human-readable name and whose value represents the required joint state.
| K | A reference to a JointIdMap to be filled with the requested joint state. It is the user responsibility to clear the map before it is filled (if required). | 
| bool XBot::ModelInterface::getVelocityTwist | ( | const std::string & | link_name, | 
| Eigen::Vector6d & | velocity | ||
| ) | const | 
Gets the velocity twist of link_name (first linear, then angular velocity).
The reference point of the velocity twist is the origin of the link itself.
| link_name | The link name | 
| velocity | The twist of the link "link_name" | 
| 
 | pure virtual | 
Gets the velocity twist of link_name (first linear, then angular velocity).
The reference point of the velocity twist is the origin of the link itself.
| link_name | The link name | 
| velocity | The twist of the link "link_name" | 
| 
 | virtual | 
Computes the velocity of the source_frame w.r.t.
the target_frame expressed in target_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| velocity | A twist computed as: v = J*qdot, where J is the relative Jacobian computed using getRelativeJacobian(source_frame, target_frame) | 
| 
 | virtual | 
Computes the velocity of the source_frame w.r.t.
the target_frame expressed in target_frame
| source_frame | The source link name. | 
| target_frame | The target link name. | 
| velocity | A twist computed as: v = J*qdot, where J is the relative Jacobian computed using getRelativeJacobian(source_frame, target_frame) | 
| 
 | protectedvirtual | 
Reimplemented from XBot::XBotInterface.
| 
 | protectedpure virtual | 
| bool XBot::ModelInterface::isFloatingBase | ( | ) | const | 
True if the robot is floating base, false if it has a fixed base.
| XBot::ModelChain & XBot::ModelInterface::leg | ( | int | leg_id | ) | 
Returns a handle to the kinematic chain corresponding to the leg n° leg_id.
The order of legs is defined in the SRDF file which was provided to ModelInterface::getModel(). If the requested chain is not defined, a dummy chain is returned and an error is displayed.
| arm_id | The requested leg id, from 0 to legs()-1 | 
| const XBot::ModelChain & XBot::ModelInterface::leg | ( | int | leg_id | ) | const | 
| bool XBot::ModelInterface::maskJacobian | ( | const std::string & | chain_name, | 
| Eigen::MatrixXd & | J | ||
| ) | const | 
Applies a mask corresponding to the specified chain to the jacobian provided as an argument.
This amounts to setting the columns of the jacobian corresponding the the chain to zero.
| chain_name | The name of the chain. | 
| J | The jacobian which the mask has to be applied to. | 
| bool XBot::ModelInterface::maskJacobian | ( | const std::string & | chain_name, | 
| KDL::Jacobian & | J | ||
| ) | const | 
Applies a mask corresponding to the specified chain to the jacobian provided as an argument.
This amounts to setting the columns of the jacobian corresponding the the chain to zero.
| chain_name | The name of the chain. | 
| J | The jacobian which the mask has to be applied to. | 
| XBot::ModelChain & XBot::ModelInterface::operator() | ( | const std::string & | chain_name | ) | 
Returns a handle to the kinematic chain named chain_name.
If such a chain is not defined, a dummy chain is returned and an error is displayed.
| chain_name | The name of the requested chain | 
| const XBot::ModelChain & XBot::ModelInterface::operator() | ( | const std::string & | chain_name | ) | const | 
| 
 | delete | 
| 
 | inlineprotected | 
| 
 | inlineprotected | 
| bool XBot::XBotInterface::setDamping | 
Sets the XBotInterface internal joint damping according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| D | The vector of input joint states. | 
| bool XBot::XBotInterface::setDamping | 
Sets the XBotInterface internal joint damping according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| K | The input JointIdMap | 
| bool XBot::XBotInterface::setDamping | 
Sets the XBotInterface internal joint damping according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| D | The input JointIdMap | 
| bool XBot::ModelInterface::setFloatingBaseAngularVelocity | ( | const Eigen::Vector3d & | floating_base_omega | ) | 
Sets the floating base angular velocity w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_omega | The angular velocity of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::setFloatingBaseAngularVelocity | ( | const KDL::Vector & | floating_base_omega | ) | 
Sets the floating base angular velocity w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_omega | The angular velocity of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::setFloatingBaseOrientation | ( | const Eigen::Matrix3d & | world_R_floating_base | ) | 
Sets the floating base orientation w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| world_R_floating_base | A rotation matrix which rotates a vector from floating base frame to world frame | 
| bool XBot::ModelInterface::setFloatingBaseOrientation | ( | const KDL::Rotation & | world_R_floating_base | ) | 
Sets the floating base orientation w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| world_R_floating_base | A rotation matrix which rotates a vector from floating base frame to world frame | 
| bool XBot::ModelInterface::setFloatingBasePose | ( | const Eigen::Affine3d & | floating_base_pose | ) | 
Sets the floating base pose w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_pose | A homogeneous transformation which transforms a point from floating base frame to world frame | 
| 
 | pure virtual | 
Sets the floating base pose w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_pose | A homogeneous transformation which transforms a point from floating base frame to world frame | 
| bool XBot::ModelInterface::setFloatingBaseState | ( | const Eigen::Affine3d & | pose, | 
| const Eigen::Vector6d & | twist | ||
| ) | 
Sets the floating base pose and twist w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| pose | The pose of the floating base w.r.t. the world | 
| twist | The twist of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::setFloatingBaseState | ( | const KDL::Frame & | pose, | 
| const KDL::Twist & | twist | ||
| ) | 
Sets the floating base pose and twist w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| pose | The pose of the floating base w.r.t. the world | 
| twist | The twist of the floating base w.r.t. the world | 
| bool XBot::ModelInterface::setFloatingBaseState | ( | XBot::ImuSensor::ConstPtr | imu, | 
| const Eigen::Matrix3d & | offset = Eigen::Matrix3d::Identity() | ||
| ) | 
Sets the floating base orientation and angular velocity w.r.t.
the world frame from an IMU sensor attached to the model. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| imu | The pose of the floating base w.r.t. the world | 
| offset | Rotation are premultiplied by this roation offset | 
| 
 | virtual | 
Sets the floating base twist w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_twist | The twist of the floating base w.r.t. the world | 
| 
 | pure virtual | 
Sets the floating base twist w.r.t.
the world frame. Note that update() must be called in order to recompute kinematics/dynamics accordingly.
| floating_base_twist | The twist of the floating base w.r.t. the world | 
| void XBot::ModelInterface::setGravity | ( | const Eigen::Vector3d & | gravity | ) | 
Sets the gravity vector expressed in the world frame.
| gravity | The gravity vector expressed in the world frame. | 
| 
 | pure virtual | 
Sets the gravity vector expressed in the world frame.
| gravity | The gravity vector expressed in the world frame. | 
| bool XBot::ModelInterface::setGravity | ( | const std::string & | reference_frame, | 
| const Eigen::Vector3d & | gravity | ||
| ) | 
Sets the gravity vector expressed in the reference_frame.
| reference_frame | The link name w.r.t. which the gravity vector will be expressed | 
| gravity | The gravity vector expressed in the reference_frame | 
| bool XBot::ModelInterface::setGravity | ( | const std::string & | reference_frame, | 
| const KDL::Vector & | gravity | ||
| ) | 
Sets the gravity vector expressed in the reference_frame.
| reference_frame | The link name w.r.t. which the gravity vector will be expressed | 
| gravity | The gravity vector expressed in the reference_frame | 
| bool XBot::XBotInterface::setJointAcceleration | 
Sets the XBotInterface internal joint accelerations according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| qddot | The vector of input joint states. | 
| bool XBot::XBotInterface::setJointAcceleration | 
Sets the XBotInterface internal joint accelerations according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qddot | The input JointIdMap | 
| bool XBot::XBotInterface::setJointAcceleration | 
Sets the XBotInterface internal joint accelerations according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qddot | The input JointIdMap | 
| bool XBot::XBotInterface::setJointEffort | 
Sets the XBotInterface internal joint efforts according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| tau | The vector of input joint states. | 
| bool XBot::XBotInterface::setJointEffort | 
Sets the XBotInterface internal joint efforts according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| tau | The input JointIdMap | 
| bool XBot::XBotInterface::setJointEffort | 
Sets the XBotInterface internal joint efforts according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| tau | The input JointIdMap | 
| bool XBot::XBotInterface::setJointPosition | 
Sets the XBotInterface internal joint positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| q | The vector of input joint states. | 
| bool XBot::XBotInterface::setJointPosition | 
Sets the XBotInterface internal joint positions according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| q | The input JointIdMap | 
| bool XBot::XBotInterface::setJointPosition | 
Sets the XBotInterface internal joint positions according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| q | The input JointIdMap | 
| bool XBot::XBotInterface::setJointVelocity | 
Sets the XBotInterface internal joint velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| qdot | The vector of input joint states. | 
| bool XBot::XBotInterface::setJointVelocity | 
Sets the XBotInterface internal joint velocities according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qdot | The input JointIdMap | 
| bool XBot::XBotInterface::setJointVelocity | 
Sets the XBotInterface internal joint velocities according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qdot | The input JointIdMap | 
| bool XBot::XBotInterface::setMotorPosition | 
Sets the XBotInterface internal motor positions according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| q | The vector of input joint states. | 
| bool XBot::XBotInterface::setMotorPosition | 
Sets the XBotInterface internal motor positions according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| q | The input JointIdMap | 
| bool XBot::XBotInterface::setMotorPosition | 
Sets the XBotInterface internal motor positions according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| q | The input JointIdMap | 
| bool XBot::XBotInterface::setMotorVelocity | 
Sets the XBotInterface internal motor velocities according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| qdot | The vector of input joint states. | 
| bool XBot::XBotInterface::setMotorVelocity | 
Sets the XBotInterface internal motor velocities according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qdot | The input JointIdMap | 
| bool XBot::XBotInterface::setMotorVelocity | 
Sets the XBotInterface internal motor velocities according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| qdot | The input JointIdMap | 
| bool XBot::XBotInterface::setStiffness | 
Sets the XBotInterface internal joint stiffness according to the provided vector, which must be ordered as specified by the getEnabledJointNames/getEnabledJointId methods.
| K | The vector of input joint states. | 
| bool XBot::XBotInterface::setStiffness | 
Sets the XBotInterface internal joint stiffness according to the input JointIdMap (i.e.
a map whose key represents the joint ID and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| K | The input JointIdMap | 
| bool XBot::XBotInterface::setStiffness | 
Sets the XBotInterface internal joint stiffness according to the input JointNameMap (i.e.
a map whose key represents the joint name and whose value represents the joint state), which can include joint states for an arbitrary subset of the whole robot.
| K | The input JointIdMap | 
| bool XBot::ModelInterface::syncFrom | ( | const XBotInterface & | other, | 
| SyncFlags... | flags | ||
| ) | 
Synchronizes the internal model state to the one of the XBotInterface given as an argument.
This can be either another ModelInterface or a RobotInterface. Flags can be specified to select a part of the state to be synchronized. ModelInterface::update() is automatcally called, so that the kinematics and dynamics of the ModelInterface is updated as well.
@usage model.syncFrom(other_model, XBot::Sync::Position, XBot::Sync::Effort) @usage model.syncFrom(other_model, XBot::Sync::Position)
| other | The RobotInterface or ModelInterface whose state is copied to this model. | 
| flags | Flags to specify what part of the state must be synchronized. By default (i.e. if this argument is omitted) the whole state is synchronized. Otherwise, an arbitrary number of flags can be specified in order to select a subset of the state. The flags must be of the enum type XBot::Sync, which can take the following values: 
 | 
| bool XBot::ModelInterface::syncFrom_no_update | ( | const XBotInterface & | other, | 
| SyncFlags... | flags | ||
| ) | 
Synchronizes the internal model state to the one of the XBotInterface given as an argument.
This can be either another ModelInterface or a RobotInterface. Flags can be specified to select a part of the state to be synchronized. As the only difference with ModelInterface::syncFrom(), ModelInterface::update() is NOT automatcally called.
@usage model.syncFrom(other_model, XBot::Sync::Position, XBot::Sync::Effort) @usage model.syncFrom(other_model, XBot::Sync::Position)
| other | The RobotInterface or ModelInterface whose state is copied to this model. | 
| flags | Flags to specify what part of the state must be synchronized. By default (i.e. if this argument is omitted) the whole state is synchronized. Otherwise, an arbitrary number of flags can be specified in order to select a subset of the state. The flags must be of the enum type XBot::Sync, which can take the following values: | 
| bool XBot::ModelInterface::update | ( | bool | update_position = true, | 
| bool | update_velocity = true, | ||
| bool | update_desired_acceleration = true | ||
| ) | 
Updates the kinematic variables of the model according to the current state of the model.
When called without arguments, it only updates joint positions (no velocities/accelerations).
| update_position | True if you want to update the positions. False otherwise. | 
| update_velocity | True if you want to update the velocities. False otherwise. | 
| update_desired_acceleration | True if you want to update the desired accelerations. False otherwise. | 
| 
 | protectedpure virtual | 
| 
 | protected | 
 1.8.17
 1.8.17