unicycle_robot.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_UNICYCLE_ROBOT_H_
24 #define SYSTEMS_UNICYCLE_ROBOT_H_
25 
27 
28 #include <cmath>
29 
30 namespace mpc_local_planner {
31 
46 class UnicycleModel : public BaseRobotSE2
47 {
48  public:
50  UnicycleModel() = default;
51 
52  // implements interface method
53  SystemDynamicsInterface::Ptr getInstance() const override { return std::make_shared<UnicycleModel>(); }
54 
55  // implements interface method
56  int getInputDimension() const override { return 2; }
57 
58  // implements interface method
60  {
61  assert(x.size() == getStateDimension());
62  assert(u.size() == getInputDimension());
63  assert(x.size() == f.size() && "UnicycleModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
64 
65  f[0] = u[0] * std::cos(x[2]);
66  f[1] = u[0] * std::sin(x[2]);
67  f[2] = u[1];
68  }
69 
70  // implements interface method
71  bool getTwistFromControl(const Eigen::Ref<const Eigen::VectorXd>& u, geometry_msgs::Twist& twist) const override
72  {
73  assert(u.size() == getInputDimension());
74  twist.linear.x = u[0];
75  twist.linear.y = twist.linear.z = 0;
76 
77  twist.angular.z = u[1];
78  twist.angular.x = twist.angular.y = 0;
79  return true;
80  }
81 };
82 
83 } // namespace mpc_local_planner
84 
85 #endif // SYSTEMS_UNICYCLE_ROBOT_H_
mpc_local_planner::UnicycleModel::getInputDimension
int getInputDimension() const override
Definition: unicycle_robot.h:96
mpc_local_planner
Definition: controller.h:44
f
f
x
Scalar * x
base_robot_se2.h
mpc_local_planner::UnicycleModel::getTwistFromControl
bool getTwistFromControl(const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override
Convert control vector to twist message.
Definition: unicycle_robot.h:111
Eigen::Ref
mpc_local_planner::UnicycleModel::dynamics
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
Definition: unicycle_robot.h:99
mpc_local_planner::BaseRobotSE2::getStateDimension
int getStateDimension() const override
Definition: base_robot_se2.h:97
mpc_local_planner::UnicycleModel::UnicycleModel
UnicycleModel()=default
Default constructor.
mpc_local_planner::UnicycleModel::getInstance
SystemDynamicsInterface::Ptr getInstance() const override
Definition: unicycle_robot.h:93


mpc_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:35:06