RML  1.0
Robotics Mathematical Library
Loading...
Searching...
No Matches
VehicleModel.h
Go to the documentation of this file.
1
8#ifndef __CTRL_VEHICLEMODEL_H__
9#define __CTRL_VEHICLEMODEL_H__
10
11#include "RMLExceptions.h"
12#include "Types.h"
13#include <algorithm>
14#include <eigen3/Eigen/Dense>
15#include <unordered_map>
16#include <vector>
17
18namespace rml {
24public:
29 VehicleModel(const std::string id);
33 virtual ~VehicleModel();
43 Eigen::MatrixXd Jacobian(const std::string& ID) noexcept(false);
50 void PositionOnInertialFrame(const Eigen::TransformationMatrix& inertialF_T_vehicleF);
68 auto VelocityVector() const -> const Eigen::Vector6d& { return velocity_; }
78 auto AccelerationVector() const -> const Eigen::Vector6d& { return acceleration_; }
84 void AttachRigidBodyFrame(const std::string& frameID, const Eigen::TransformationMatrix& vehicleF_T_frameID);
90 Eigen::TransformationMatrix TransformationMatrix(const std::string& frameID) noexcept(false);
97 Eigen::TransformationMatrix TransformationMatrix(const std::string& frameID_j, const std::string& frameID_k);
102 auto IsModelInizialized() const -> bool { return modelInitialized_; }
107 auto ControlVector() const -> const Eigen::Vector6d& { return controlRef_; }
117 auto ID() -> std::string& { return id_; }
122 auto ID() const -> const std::string& { return id_; }
123
124protected:
127 std::unordered_map<std::string, Eigen::TransformationMatrix> rigidBodyFrames_;
132 std::unordered_map<std::string, Eigen::MatrixXd> jacobians_;
133 std::unordered_map<std::string, Eigen::TransformationMatrix> transformation_;
136 std::string id_;
137};
138}
139
140#endif /* __CTRL_VEHICLEMODEL_H__ */
This class extends the Eigen::Matrix3d.
Definition RotMatrix.h:26
This class extends the Eigen::Matrix4d.
Definition TransfMatrix.h:26
A 6d vector generally used for containing pose [x y z r p y] or velocity [vx vy vz wx wy wz] vectors.
Definition Vector6d.h:18
Vehicle Model base class.
Definition VehicleModel.h:23
auto VelocityVector() -> Eigen::Vector6d &
Set the base position The method updates the internal base velocity state. This method should be call...
Definition VehicleModel.h:62
auto ID() const -> const std::string &
Method returning the id.
Definition VehicleModel.h:122
VehicleModel(const std::string id)
Default constructor.
std::unordered_map< std::string, Eigen::TransformationMatrix > rigidBodyFrames_
map of the attached body frames
Definition VehicleModel.h:127
Eigen::Vector6d acceleration_
vehicle acceleration
Definition VehicleModel.h:130
auto IsModelInizialized() const -> bool
Method returning whether the model is initialized.
Definition VehicleModel.h:102
auto AccelerationVector() const -> const Eigen::Vector6d &
Method returning the acceleration wrt to the vehicle frame.
Definition VehicleModel.h:78
Eigen::Vector6d controlRef_
vehicle control vector
Definition VehicleModel.h:131
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::TransformationMatrix TransformationMatrix(const std::string &frameID) noexcept(false)
Method returning the transformation matrix related to the frame id in input.
auto AccelerationVector() -> Eigen::Vector6d &
set the vehicle acceleration expressed wrt to the vehicle frame
Definition VehicleModel.h:73
Eigen::Matrix6d vJv_
vehicle jacobians
Definition VehicleModel.h:134
bool modelInitialized_
boolean stating whether the model is initialized
Definition VehicleModel.h:125
virtual ~VehicleModel()
Default destructor.
Eigen::MatrixXd Jacobian(const std::string &ID) noexcept(false)
Method returning the jacobian related to the frame id in input.
std::unordered_map< std::string, Eigen::MatrixXd > jacobians_
map of vehicle jacobians
Definition VehicleModel.h:132
Eigen::Vector6d velocity_
vehicle velocity
Definition VehicleModel.h:129
auto PositionOnInertialFrame() const -> const Eigen::TransformationMatrix &
Get the inertialF_T_vehicleF independently from the DOF of the vehicle.
Definition VehicleModel.h:56
Eigen::RotationMatrix I3_
identity matrix
Definition VehicleModel.h:135
Eigen::TransformationMatrix inertialF_T_vehicleF_
vehicle position w.r.t the inertial frame
Definition VehicleModel.h:128
std::string id_
vehicle id
Definition VehicleModel.h:136
void PositionOnInertialFrame(const Eigen::TransformationMatrix &inertialF_T_vehicleF)
Set the base position The method updates the internal base position state. This method should be call...
bool isMapInitialized_
boolean stating whether the transformation and jacobian maps are initialized
Definition VehicleModel.h:126
void AttachRigidBodyFrame(const std::string &frameID, const Eigen::TransformationMatrix &vehicleF_T_frameID)
Method adding a rigid body frame to the vehicle.
std::unordered_map< std::string, Eigen::TransformationMatrix > transformation_
map of vehicle transformations
Definition VehicleModel.h:133
void Jacobian(Eigen::Matrix6d J)
Jacobian initialization.
auto ControlVector() -> Eigen::Vector6d &
Method setting the control vector.
Definition VehicleModel.h:112
auto ID() -> std::string &
Method setting the id.
Definition VehicleModel.h:117
auto VelocityVector() const -> const Eigen::Vector6d &
Get the complete 6D velocity, in the form of [x_dot y_dot z_dot wx wy wz], independently from the Dof...
Definition VehicleModel.h:68
auto ControlVector() const -> const Eigen::Vector6d &
Method returning the vehicle control vector.
Definition VehicleModel.h:107
This namespace is used to extend the Eigen Dense library functionalities.
Definition RotMatrix.h:13
Eigen::Matrix< double, 6, 6 > Matrix6d
Definition Types.h:36
Types and algorithms for robotic mobile manipulation.
Definition ArmModel.h:19