23 #ifndef SYSTEMS_SIMPLE_CAR_H_ 24 #define SYSTEMS_SIMPLE_CAR_H_ 62 SystemDynamicsInterface::Ptr
getInstance()
const override {
return std::make_shared<SimpleCarModel>(); }
72 assert(x.size() == f.size() &&
"SimpleCarModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
74 f[0] = u[0] * std::cos(x[2]);
75 f[1] = u[0] * std::sin(x[2]);
83 twist.linear.x = u[0];
84 twist.linear.y = twist.linear.z = 0;
86 twist.angular.z = u[1];
87 twist.angular.x = twist.angular.y = 0;
128 SystemDynamicsInterface::Ptr
getInstance()
const override {
return std::make_shared<SimpleCarFrontWheelDrivingModel>(); }
135 assert(x.size() == f.size() &&
136 "SimpleCarFrontWheelDrivingModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
138 f[0] = u[0] * std::cos(x[2]);
139 f[1] = u[0] * std::sin(x[2]);
146 #endif // SYSTEMS_SIMPLE_CAR_H_
void setWheelbase(double wheelbase)
Set wheelbase.
Simple car model with front wheel actuation.
double getWheelbase() const
Get wheelbase.
SystemDynamicsInterface::Ptr getInstance() const override
SystemDynamicsInterface::Ptr getInstance() const override
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
SimpleCarModel(double wheelbase)
Constructs model with given wheelbase.
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
SimpleCarModel()=default
Default constructor.
Specialization of RobotDynamicsInterface for mobile robots operating in SE2.
int getStateDimension() const override
bool getTwistFromControl(const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override
Convert control vector to twist message.
int getInputDimension() const override
SimpleCarFrontWheelDrivingModel(double wheelbase)
Constructs model with given wheelbase.