Robot Model class, to evaluate either mobile or fixed manipulators total transformation matrices and jacobians.
More...
|
| | RobotModel (Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID) |
| | Constructor for fixed robot model.
|
| |
| | RobotModel (Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID, Eigen::MatrixXd bodyF_JBodyFrame) |
| | Constructor for mobile robot model.
|
| |
| virtual | ~RobotModel () |
| | Default deconstructor.
|
| |
| auto | Dof () const -> int |
| | Returns the number of total degrees of fredoom of the system composed (both of the base if mobile and the arms).
|
| |
| bool | LoadArm (const std::shared_ptr< ArmModel > &arm, const Eigen::TransformationMatrix &bodyFrameToArm) noexcept(false) |
| | Loads an arm in the robot model.
|
| |
| auto | BodyFrameID () const -> const std::string & |
| | Method to get the body Frame id.
|
| |
| void | PositionOnInertialFrame (const Eigen::TransformationMatrix &inertialF_T_bodyF) |
| | Method to set the new body Frame position.
|
| |
| void | AttachRigidBodyFrame (const std::string &frameID, const std::string &attachedFrameID, const Eigen::TransformationMatrix &frameToAttachID_T_frameID) noexcept(false) |
| | Method adding a rigid body frame attached to the input frame id .
|
| |
| bool | CheckArm (const std::string &armID) const |
| |
| auto | IsMobile () const -> bool |
| | Method checking whether the robot model has a mobile body Frame .
|
| |
| Eigen::MatrixXd | CartesianJacobian (const std::string &frameID) noexcept(false) |
| | Method computing the jacobian observed by the world frame and projected on the body Frame of the input frameID.
|
| |
| Eigen::MatrixXd | JointSpaceJacobian (const std::string &armID) noexcept(false) |
| | Method computing the joint space jacobian of the input arm ID.
|
| |
| Eigen::MatrixXd | ManipulabilityJacobian (const std::string &frameID) noexcept(false) |
| | Method computing the manipulability jacobian of the input arm ID.
|
| |
| double | Manipulability (const std::string &frameID) noexcept(false) |
| | Method returning the manipulabity value for the jacobian related to the input frameID.
|
| |
| Eigen::MatrixXd | DexterityJacobian (const std::string &frameID) noexcept(false) |
| | Method computing the dexterity jacobian of the input arm ID.
|
| |
| double | Dexterity (const std::string &frameID) noexcept(false) |
| | Method returning the dexterity value for the jacobian related to the input frameID.
|
| |
| Eigen::TransformationMatrix | TransformationMatrix (const std::string &frameID) noexcept(false) |
| | Method returning a transformation matrix of the robot model.
.
|
| |
| Eigen::TransformationMatrix | TransformationMatrix (const std::string &frameID_j, const std::string &frameID_k) |
| | Method returing a transformation matrix from frameID_j to frameID_k, i.e. jTk.
.
|
| |
| const std::shared_ptr< ArmModel > & | Arm (const std::string &ID) const noexcept(false) |
| | Method returning shared pointer to one of the loaded arm.
|
| |
| void | PositionVector (Eigen::VectorXd &position) noexcept(false) |
| | Method setting the position vector of the whole robot model.
|
| |
| Eigen::VectorXd | PositionVector () |
| | Method returning the position vector of the whole robot model.
|
| |
| void | VelocityVector (const Eigen::VectorXd &velocity) noexcept(false) |
| | Method setting the velocity vector of the whole robot model.
|
| |
| Eigen::VectorXd | VelocityVector () |
| | Method returning the velocity vector of the whole robot model.
|
| |
| Eigen::VectorXd | AccelerationVector () |
| | Method returning the acceleration vector of the whole robot model.
|
| |
| void | AccelerationVector (const Eigen::VectorXd &acceleration) noexcept(false) |
| | Method setting the acceleration vector of the whole robot model.
|
| |
| void | PositionVector (const std::string &partID, const Eigen::VectorXd &position) noexcept(false) |
| | Method setting the position vector for a robot part (joint postion for arm and cartesian position in case of mobile body Frame).
|
| |
| Eigen::VectorXd | PositionVector (const std::string &partID) noexcept(false) |
| | Method returning the position of the input part (i.e. joint position for arm and cartesian position in case if of mobile body Frame)
|
| |
| void | VelocityVector (const std::string &partID, const Eigen::VectorXd &velocity) noexcept(false) |
| | Method setting the velocity vector for a robot part (joint velocity for arm and cartesian velocity in case of mobile body Frame ).
|
| |
| Eigen::VectorXd | VelocityVector (const std::string &partID) noexcept(false) |
| | GetVelocityVector Method returning the velocity of the input part (i.e. joints velocity for arm and cartesian velocity in case of mobile body Frame )
|
| |
| void | AccelerationVector (const std::string &partID, const Eigen::VectorXd &acceleration) noexcept(false) |
| | Method setting the acceleration vector for a robot part (joints acceleration for arm and cartesian acceleration in case of mobile body Frame ).
|
| |
| Eigen::VectorXd | AccelerationVector (const std::string &partID) noexcept(false) |
| | Method returning the position of the input part (i.e. joint acceleration for arm and cartesian acceleration in case of mobile body Frame)
|
| |
| void | ControlVector (const Eigen::VectorXd &y) noexcept(false) |
| | Method setting the control vector of the whole robot model.
|
| |
| Eigen::VectorXd | ControlVector (const std::string &partID) noexcept(false) |
| | Method returning the control vector of the input part of robot model.
|
| |
Robot Model class, to evaluate either mobile or fixed manipulators total transformation matrices and jacobians.
This class provides a container for storing a multi-arm robot model. The robot could either be mobile one (hence characterized by a moving body Frame) or a static one (hence with a fixed body frame). Use the constructor a Jacobian for the body Frame is provided as input in the constructor).
In order to add arm to the robot the method LoadArm() is provided. It is in addition possible to add rigid body frames to the robot frames by using the method AttachedRigidBodyFrame().
The robot model contains an internal unique representation of the whole system, hence all the information about the robot model are given by organizing the vectors in an order a priori defined, where the moving body frame, if present, corresponds to the first 6 position of the vector. It is possible to obtain unified information about the robot position, velocity, acceleration and control by using the given methods (e.g. PositionVector() to know the position of the whole system) but methods to obtain information of a single part of the robot model are provided (e.g. PositionVector(partId) for the position of a part of the robot method, such function takes as input the id of the desired part).
The user must update the feedback for the arms and the mobile platform, if present, by using the methods PositionVector() = feedbackVector if the feedback for the whole robot are in a unique vector or PositionVector(partID) = part_feedbackVecotr if the data are separated into vectors. Similar methods are provided also with the purpose of setting the feedback in velocity and acceleration and control. For setting uniquely the body frame position, the dedicated method PositionOnInertialFrame() is provided.
By exploiting the methods provided in the ArmModel and VehicleModel class, the robot model is able to provide the transformation matrices and the jacobians for all the frames defined in the robot. For this purpose the methods TransformationMatrix() and CartesianJacobian() are provided. These methods take as input the id of the frame for which computing the matrices.
The id must be provieded according the following logic:
- joint n-th: armID + rml::FrameID::Joint + "n"
- rigidBody attached on arm: armID + "_" + "rigidBodyID"
- rigid body attached on body frame: robotName + "_" + rigidBodyID
It is worth noticing that the transformation matrices are expressed wrt to the world frame meanwhile the jacobians are observed by the inertial frame and expressed wrt to the body frame. In addition the method TransformationMatrix() is provided in order to compute the transformation matrices in between the two frames identified by the input ids.
Furthermore the two methods JointSpaceJacobian() and ManipulabilityJacobian() are provided.
The former takes as input the armID and returns the related joint space jacobian. The latter takes as input a frame id and returns the related manipulability jacobian. In order to obtain the manipulability value for a frame the method Manipulability() must be used
It is worth noticing that the jacobians given by the RobotModel takes into account the degrees of freedom of the whole robot (hence of all the arms and of the moving platform, if present) in the aforementioned a priori defined order.
Example of frame id:
- "youbot_Joint_0" for the first joint of the arm "youbot"
- "youbot_tool0" for a rigid body frame "tool0" attached to the arm "youbot"