23 #ifndef SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_ 24 #define SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_ 26 #include <corbo-core/types.h> 28 #include <geometry_msgs/Twist.h> 49 using Ptr = std::shared_ptr<RobotDynamicsInterface>;
151 #endif // SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_
virtual void getPositionFromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y) const =0
Convert state vector to position (x,y)
virtual void getSteadyStateFromPoseSE2(const teb_local_planner::PoseSE2 &pose, Eigen::Ref< Eigen::VectorXd > x) const
Convert PoseSE2 to steady state.
virtual bool getTwistFromControl(const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const =0
Convert control vector to twist message.
virtual void getPoseSE2FromState(const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y, double &theta) const =0
Convert state vector to pose (x,y,theta)
virtual bool mergeStateFeedbackAndOdomFeedback(const teb_local_planner::PoseSE2 &odom_pose, const geometry_msgs::Twist &odom_twist, Eigen::Ref< Eigen::VectorXd > x) const =0
Merge custom state feedback with pose and twist feedback.
virtual void getPoseSE2FromState(const Eigen::Ref< const Eigen::VectorXd > &x, teb_local_planner::PoseSE2 &pose) const
Convert state vector to PoseSE2 object.
Specialization of SystemDynamicsInterface for mobile robots.
virtual void getSteadyStateFromPoseSE2(double pos_x, double pos_y, double theta, Eigen::Ref< Eigen::VectorXd > x) const =0
Convert pose (x,y,theta) to steady state.
std::shared_ptr< SystemDynamicsInterface > Ptr