base_robot_se2.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_BASE_ROBOT_SE2_H_
24 #define SYSTEMS_BASE_ROBOT_SE2_H_
25 
27 
28 namespace mpc_local_planner {
29 
44 {
45  public:
46  using Ptr = std::shared_ptr<BaseRobotSE2>;
47 
49  BaseRobotSE2() = default;
50 
51  // implements interface method
53 
54  // implements interface method
55  int getInputDimension() const override = 0;
56  // implements interface method
57  int getStateDimension() const override { return 3; }
58 
59  // implements interface method
60  bool isContinuousTime() const override { return true; }
61 
62  // implements interface method
63  bool isLinear() const override { return false; }
64 
65  // implements interface method
66  void getPositionFromState(const Eigen::Ref<const Eigen::VectorXd>& x, double& pos_x, double& pos_y) const override
67  {
68  assert(x.size() == getStateDimension());
69  pos_x = x[0];
70  pos_y = x[1];
71  }
72 
73  // implements interface method
74  void getPoseSE2FromState(const Eigen::Ref<const Eigen::VectorXd>& x, double& pos_x, double& pos_y, double& theta) const override
75  {
76  assert(x.size() == getStateDimension());
77  pos_x = x[0];
78  pos_y = x[1];
79  theta = x[2];
80  }
81 
82  // implements interface method
83  void getSteadyStateFromPoseSE2(double pos_x, double pos_y, double theta, Eigen::Ref<Eigen::VectorXd> x) const override
84  {
85  assert(x.size() == getStateDimension());
86  x[0] = pos_x;
87  x[1] = pos_y;
88  x[2] = theta;
89  if (x.size() > 3) x.tail(x.size() - 3).setZero();
90  }
91 
92  // implements interface method
93  virtual bool mergeStateFeedbackAndOdomFeedback(const teb_local_planner::PoseSE2& odom_pose, const geometry_msgs::Twist& odom_twist,
94  Eigen::Ref<Eigen::VectorXd> x) const override
95  {
96  assert(x.size() == getStateDimension());
97  x[0] = odom_pose.x();
98  x[1] = odom_pose.y();
99  x[2] = odom_pose.theta();
100  return true;
101  }
102 
103  // implements interface method
105 };
106 
107 } // namespace mpc_local_planner
108 
109 #endif // SYSTEMS_BASE_ROBOT_SE2_H_
bool isContinuousTime() const override
Scalar * x
f
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


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