kinematic_bicycle_model.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_KINEMATIC_BICYCLE_MODEL_H_
24 #define SYSTEMS_KINEMATIC_BICYCLE_MODEL_H_
25 
27 
28 #include <cmath>
29 
30 namespace mpc_local_planner {
31 
50 {
51  public:
54 
56  KinematicBicycleModelVelocityInput(double lr, double lf) : _lr(lr), _lf(lf) {}
57 
58  // implements interface method
59  SystemDynamicsInterface::Ptr getInstance() const override { return std::make_shared<KinematicBicycleModelVelocityInput>(); }
60 
61  // implements interface method
62  int getInputDimension() const override { return 2; }
63 
64  // implements interface method
66  {
67  assert(x.size() == getStateDimension());
68  assert(u.size() == getInputDimension());
69  assert(x.size() == f.size() &&
70  "KinematicBicycleModelVelocityInput::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
71 
72  double beta = std::atan(_lr / (_lf + _lr) * std::tan(u[1]));
73 
74  f[0] = u[0] * std::cos(x[2] + beta);
75  f[1] = u[0] * std::sin(x[2] + beta);
76  f[2] = u[0] * std::sin(beta) / _lr;
77  }
78 
79  // implements interface method
80  bool getTwistFromControl(const Eigen::Ref<const Eigen::VectorXd>& u, geometry_msgs::Twist& twist) const override
81  {
82  assert(u.size() == getInputDimension());
83  twist.linear.x = u[0];
84  twist.linear.y = twist.linear.z = 0;
85 
86  twist.angular.z = u[1]; // warning, this is the angle and not the angular vel
87  twist.angular.x = twist.angular.y = 0;
88 
89  return true;
90  }
91 
93  void setParameters(double lr, double lf)
94  {
95  _lr = lr;
96  _lf = lf;
97  }
99  double getLengthFront() const { return _lf; }
101  double getLengthRear() const { return _lr; }
102 
103  protected:
104  double _lr = 1.0;
105  double _lf = 1.0;
106 };
107 
108 } // namespace mpc_local_planner
109 
110 #endif // SYSTEMS_KINEMATIC_BICYCLE_MODEL_H_
Kinematic Bicycle Model with Velocity Input.
void setParameters(double lr, double lf)
Set parameters.
double getLengthFront() const
Get length between COG and front axle.
bool getTwistFromControl(const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override
Convert control vector to twist message.
double getLengthRear() const
Get length between COG and rear axle.
KinematicBicycleModelVelocityInput()=default
Default constructor.
KinematicBicycleModelVelocityInput(double lr, double lf)
Constructs model with given wheelbase.
SystemDynamicsInterface::Ptr getInstance() 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
int getStateDimension() const override


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