23 #ifndef SYSTEMS_BASE_ROBOT_SE2_H_ 24 #define SYSTEMS_BASE_ROBOT_SE2_H_ 46 using Ptr = std::shared_ptr<BaseRobotSE2>;
63 bool isLinear()
const override {
return false; }
89 if (x.size() > 3) x.tail(x.size() - 3).setZero();
99 x[2] = odom_pose.
theta();
109 #endif // SYSTEMS_BASE_ROBOT_SE2_H_ bool isContinuousTime() const override
int getInputDimension() const override=0
void getPoseSE2FromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y, double &theta) const override
Convert state vector to pose (x,y,theta)
corbo::SystemDynamicsInterface::Ptr getInstance() const override=0
virtual bool mergeStateFeedbackAndOdomFeedback(const teb_local_planner::PoseSE2 &odom_pose, const geometry_msgs::Twist &odom_twist, Eigen::Ref< Eigen::VectorXd > x) const override
Merge custom state feedback with pose and twist feedback.
bool isLinear() const override
Specialization of RobotDynamicsInterface for mobile robots operating in SE2.
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override=0
void getSteadyStateFromPoseSE2(double pos_x, double pos_y, double theta, Eigen::Ref< Eigen::VectorXd > x) const override
Convert pose (x,y,theta) to steady state.
void getPositionFromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y) const override
Convert state vector to position (x,y)
BaseRobotSE2()=default
Default constructor.
Specialization of SystemDynamicsInterface for mobile robots.
int getStateDimension() const override
std::shared_ptr< SystemDynamicsInterface > Ptr