Go to the documentation of this file.
23 #ifndef SYSTEMS_BASE_ROBOT_SE2_H_
24 #define SYSTEMS_BASE_ROBOT_SE2_H_
43 class BaseRobotSE2 :
public RobotDynamicsInterface
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();
109 #endif // SYSTEMS_BASE_ROBOT_SE2_H_
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)
std::shared_ptr< SystemDynamicsInterface > Ptr
bool isContinuousTime() const override
BaseRobotSE2()=default
Default constructor.
corbo::SystemDynamicsInterface::Ptr getInstance() const override=0
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override=0
int getStateDimension() const override
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.
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.
std::shared_ptr< BaseRobotSE2 > Ptr
void getPositionFromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y) const override
Convert state vector to position (x,y)
bool isLinear() const override
mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06