robot_dynamics_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020, Christoph Rösmann, All rights reserved.
6  *
7  * This program is free software: you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation, either version 3 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program. If not, see <https://www.gnu.org/licenses/>.
19  *
20  * Authors: Christoph Rösmann
21  *********************************************************************/
22 
23 #ifndef SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_
24 #define SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_
25 
26 #include <corbo-core/types.h>
28 #include <geometry_msgs/Twist.h>
30 
31 #include <memory>
32 
33 namespace mpc_local_planner {
34 
47 {
48  public:
49  using Ptr = std::shared_ptr<RobotDynamicsInterface>;
50 
58  virtual void getPositionFromState(const Eigen::Ref<const Eigen::VectorXd>& x, double& pos_x, double& pos_y) const = 0;
59 
68  virtual void getPoseSE2FromState(const Eigen::Ref<const Eigen::VectorXd>& x, double& pos_x, double& pos_y, double& theta) const = 0;
69 
77  {
78  getPoseSE2FromState(x, pose.x(), pose.y(), pose.theta());
79  }
80 
98  virtual void getSteadyStateFromPoseSE2(double pos_x, double pos_y, double theta, Eigen::Ref<Eigen::VectorXd> x) const = 0;
99 
109  {
110  getSteadyStateFromPoseSE2(pose.x(), pose.y(), pose.theta(), x);
111  }
112 
125  virtual bool getTwistFromControl(const Eigen::Ref<const Eigen::VectorXd>& u, geometry_msgs::Twist& twist) const = 0;
126 
143  virtual bool mergeStateFeedbackAndOdomFeedback(const teb_local_planner::PoseSE2& odom_pose, const geometry_msgs::Twist& odom_twist,
144  Eigen::Ref<Eigen::VectorXd> x) const = 0;
145 
146  virtual void reset() {}
147 };
148 
149 } // namespace mpc_local_planner
150 
151 #endif // SYSTEMS_ROBOT_DYNAMICS_INTERFACE_H_
Scalar * x
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


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:53:18