RML  1.0
Robotics Mathematical Library
Loading...
Searching...
No Matches
RobotModel.h
Go to the documentation of this file.
1
7#ifndef INCLUDE_RML_ROBOTMODEL_H_
8#define INCLUDE_RML_ROBOTMODEL_H_
9
10#include <memory>
11#include <vector>
12
13#include "ArmModel.h"
14#include "RMLDefines.h"
15#include "RMLExceptions.h"
16#include "VehicleModel.h"
17
18namespace rml {
19
75public:
81 RobotModel(Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID);
88 RobotModel(Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID, Eigen::MatrixXd bodyF_JBodyFrame);
92 virtual ~RobotModel();
97 auto Dof() const -> int { return DoF_; }
109 bool LoadArm(const std::shared_ptr<ArmModel>& arm, const Eigen::TransformationMatrix& bodyFrameToArm) noexcept(false);
115 auto BodyFrameID() const -> const std::string& { return bodyFrameID_; }
126 void AttachRigidBodyFrame(const std::string& frameID, const std::string& attachedFrameID, const Eigen::TransformationMatrix& frameToAttachID_T_frameID) noexcept(false);
132 bool CheckArm(const std::string& armID) const;
137 auto IsMobile() const -> bool { return isMobileRobot_; }
138
139 /*
140 * For CartesianJacobian, JointSpaceJacobian, ManipulabilityJacobian and TransformationMatrix the id must be provieded according the following logic:
141 * - n-th joint: armID + rml::FrameID::Joint + "n"
142 * - rigidBody attached on arm: armID + "_" + "rigidBodyID"
143 * - rigid body attached on body frame: robotName + "_" + rigidBodyID
144 */
150 Eigen::MatrixXd CartesianJacobian(const std::string& frameID) noexcept(false);
156 Eigen::MatrixXd JointSpaceJacobian(const std::string& armID) noexcept(false);
162 Eigen::MatrixXd ManipulabilityJacobian(const std::string& frameID) noexcept(false);
168 double Manipulability(const std::string& frameID) noexcept(false);
174 Eigen::MatrixXd DexterityJacobian(const std::string& frameID) noexcept(false);
180 double Dexterity(const std::string& frameID) noexcept(false);
187 Eigen::TransformationMatrix TransformationMatrix(const std::string& frameID) noexcept(false);
194 Eigen::TransformationMatrix TransformationMatrix(const std::string& frameID_j, const std::string& frameID_k);
200 const std::shared_ptr<ArmModel>& Arm(const std::string& ID) const noexcept(false);
205 void PositionVector(Eigen::VectorXd& position) noexcept(false);
210 Eigen::VectorXd PositionVector();
215 void VelocityVector(const Eigen::VectorXd& velocity) noexcept(false);
220 Eigen::VectorXd VelocityVector();
225 Eigen::VectorXd AccelerationVector();
230 void AccelerationVector(const Eigen::VectorXd& acceleration) noexcept(false);
235 void PositionVector(const std::string& partID, const Eigen::VectorXd& position) noexcept(false);
242 Eigen::VectorXd PositionVector(const std::string& partID) noexcept(false);
247 void VelocityVector(const std::string& partID, const Eigen::VectorXd& velocity) noexcept(false);
254 Eigen::VectorXd VelocityVector(const std::string& partID) noexcept(false);
259 void AccelerationVector(const std::string& partID, const Eigen::VectorXd& acceleration) noexcept(false);
266 Eigen::VectorXd AccelerationVector(const std::string& partID) noexcept(false);
271 void ControlVector(const Eigen::VectorXd& y) noexcept(false);
277 Eigen::VectorXd ControlVector(const std::string& partID) noexcept(false);
278
279protected:
285 Eigen::MatrixXd ArmJacobian(const std::string& frameID) const noexcept(false);
291 Eigen::Matrix6d BaseJacobian(const std::string& frameID) const;
292
293 std::shared_ptr<VehicleModel> robotBase_;
294 std::map<std::string, std::shared_ptr<ArmModel>> armsModel_;
295 std::unordered_map<std::string, Eigen::TransformationMatrix> bodyFrameToArm_;
296 std::string bodyFrameID_;
298 int DoF_;
300};
301
302} /* namespace rml */
303
304#endif /* INCLUDE_RML_ROBOTMODEL_H_ */
This class extends the Eigen::Matrix4d.
Definition TransfMatrix.h:26
Robot Model class, to evaluate either mobile or fixed manipulators total transformation matrices and ...
Definition RobotModel.h:74
void VelocityVector(const Eigen::VectorXd &velocity) noexcept(false)
Method setting the velocity vector of the whole robot model.
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 inpu...
RobotModel(Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID)
Constructor for fixed robot model.
void ControlVector(const Eigen::VectorXd &y) noexcept(false)
Method setting the control vector of the whole robot model.
Eigen::TransformationMatrix TransformationMatrix(const std::string &frameID) noexcept(false)
Method returning a transformation matrix of the robot model. .
double Dexterity(const std::string &frameID) noexcept(false)
Method returning the dexterity value for the jacobian related to the input frameID.
void PositionOnInertialFrame(const Eigen::TransformationMatrix &inertialF_T_bodyF)
Method to set the new body Frame position.
std::map< std::string, std::shared_ptr< ArmModel > > armsModel_
map of the loaded map
Definition RobotModel.h:294
bool LoadArm(const std::shared_ptr< ArmModel > &arm, const Eigen::TransformationMatrix &bodyFrameToArm) noexcept(false)
Loads an arm in the robot model.
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::VectorXd AccelerationVector()
Method returning the acceleration vector of the whole robot model.
Eigen::MatrixXd ArmJacobian(const std::string &frameID) const noexcept(false)
Method returning the isolated arm jacobian for the input frameID.
bool CheckArm(const std::string &armID) const
std::string bodyFrameID_
ID of the body Frame.
Definition RobotModel.h:296
bool isMobileRobot_
boolean stating wheter the robot is a mobile one
Definition RobotModel.h:299
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 ac...
void PositionVector(Eigen::VectorXd &position) noexcept(false)
Method setting the position vector of the whole robot model.
Eigen::VectorXd VelocityVector()
Method returning the velocity vector of the whole robot model.
void AccelerationVector(const Eigen::VectorXd &acceleration) noexcept(false)
Method setting the acceleration vector of the whole robot model.
const std::shared_ptr< ArmModel > & Arm(const std::string &ID) const noexcept(false)
Method returning shared pointer to one of the loaded arm.
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 .
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. .
Eigen::VectorXd ControlVector(const std::string &partID) noexcept(false)
Method returning the control vector of the input part of robot model.
Eigen::Matrix6d BaseJacobian(const std::string &frameID) const
Method returning the isolated body Frame jacobian for the input frameID.
Eigen::MatrixXd JointSpaceJacobian(const std::string &armID) noexcept(false)
Method computing the joint space jacobian of the input arm ID.
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 accele...
auto Dof() const -> int
Returns the number of total degrees of fredoom of the system composed (both of the base if mobile and...
Definition RobotModel.h:97
auto BodyFrameID() const -> const std::string &
Method to get the body Frame id.
Definition RobotModel.h:115
std::unordered_map< std::string, Eigen::TransformationMatrix > bodyFrameToArm_
map of the transformation matrix from the arm bases to the body Frame
Definition RobotModel.h:295
Eigen::MatrixXd DexterityJacobian(const std::string &frameID) noexcept(false)
Method computing the dexterity jacobian of the input arm ID.
auto IsMobile() const -> bool
Method checking whether the robot model has a mobile body Frame .
Definition RobotModel.h:137
int DoF_
total degrees of freedom of the robot
Definition RobotModel.h:298
Eigen::TransformationMatrix inertialF_T_bodyF_
body Frame transformaion matrix
Definition RobotModel.h:297
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 i...
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 c...
Eigen::VectorXd PositionVector()
Method returning the position vector of the whole robot model.
virtual ~RobotModel()
Default deconstructor.
RobotModel(Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID, Eigen::MatrixXd bodyF_JBodyFrame)
Constructor for mobile robot model.
std::shared_ptr< VehicleModel > robotBase_
the model of the body Frame;
Definition RobotModel.h:293
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...
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 ...
Eigen::Matrix< double, 6, 6 > Matrix6d
Definition Types.h:36
Types and algorithms for robotic mobile manipulation.
Definition ArmModel.h:19