23 #ifndef SYSTEMS_UNICYCLE_ROBOT_H_ 24 #define SYSTEMS_UNICYCLE_ROBOT_H_ 53 SystemDynamicsInterface::Ptr
getInstance()
const override {
return std::make_shared<UnicycleModel>(); }
63 assert(x.size() == f.size() &&
"UnicycleModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
65 f[0] = u[0] * std::cos(x[2]);
66 f[1] = u[0] * std::sin(x[2]);
74 twist.linear.x = u[0];
75 twist.linear.y = twist.linear.z = 0;
77 twist.angular.z = u[1];
78 twist.angular.x = twist.angular.y = 0;
85 #endif // SYSTEMS_UNICYCLE_ROBOT_H_
bool getTwistFromControl(const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override
Convert control vector to twist message.
SystemDynamicsInterface::Ptr getInstance() const override
int getInputDimension() const override
Specialization of RobotDynamicsInterface for mobile robots operating in SE2.
UnicycleModel()=default
Default constructor.
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
int getStateDimension() const override