Simple car model. More...
#include <simple_car.h>

Public Member Functions | |
| void | dynamics (const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override |
| int | getInputDimension () const override |
| SystemDynamicsInterface::Ptr | getInstance () const override |
| bool | getTwistFromControl (const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override |
| Convert control vector to twist message. More... | |
| double | getWheelbase () const |
| Get wheelbase. More... | |
| void | setWheelbase (double wheelbase) |
| Set wheelbase. More... | |
| SimpleCarModel ()=default | |
| Default constructor. More... | |
| SimpleCarModel (double wheelbase) | |
| Constructs model with given wheelbase. More... | |
Public Member Functions inherited from mpc_local_planner::BaseRobotSE2 | |
| BaseRobotSE2 ()=default | |
| Default constructor. More... | |
| 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) More... | |
| void | getPositionFromState (const Eigen::Ref< const Eigen::VectorXd > &x, double &pos_x, double &pos_y) const override |
| Convert state vector to position (x,y) More... | |
| int | getStateDimension () const override |
| 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. More... | |
| bool | isContinuousTime () const override |
| bool | isLinear () const override |
| 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. More... | |
Public Member Functions inherited from mpc_local_planner::RobotDynamicsInterface | |
| virtual void | getPoseSE2FromState (const Eigen::Ref< const Eigen::VectorXd > &x, teb_local_planner::PoseSE2 &pose) const |
| Convert state vector to PoseSE2 object. More... | |
| virtual void | getSteadyStateFromPoseSE2 (const teb_local_planner::PoseSE2 &pose, Eigen::Ref< Eigen::VectorXd > x) const |
| Convert PoseSE2 to steady state. More... | |
| virtual void | reset () |
Public Member Functions inherited from corbo::SystemDynamicsInterface | |
| virtual double | getDeadTime () const |
| virtual void | getLinearA (const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &A) const |
| virtual void | getLinearB (const StateVector &x0, const ControlVector &u0, Eigen::MatrixXd &B) const |
| void | setLinearizationMethod (std::shared_ptr< FiniteDifferencesInterface > lin_method) |
| SystemDynamicsInterface () | |
| virtual | ~SystemDynamicsInterface ()=default |
Protected Attributes | |
| double | _wheelbase = 1.0 |
Additional Inherited Members | |
Public Types inherited from mpc_local_planner::BaseRobotSE2 | |
| using | Ptr = std::shared_ptr< BaseRobotSE2 > |
Public Types inherited from mpc_local_planner::RobotDynamicsInterface | |
| using | Ptr = std::shared_ptr< RobotDynamicsInterface > |
Public Types inherited from corbo::SystemDynamicsInterface | |
| typedef Eigen::VectorXd | ControlVector |
| typedef std::shared_ptr< SystemDynamicsInterface > | Ptr |
| typedef Eigen::VectorXd | StateVector |
Simple car model.
This class implements the dynamics for a simple car model in which the rear wheels are actuated. The front wheels are the steering wheels (for wheelbase > 0). The state vector [x, y, theta] is defined at the center of the rear axle. See [1,2] for a mathematical description and a figure.
[1] S. M. LaValle, Planning Algorithms, Cambridge University Press, 2006. (Chapter 13, http://planning.cs.uiuc.edu/) [2] A. De Luca et al., Feedback Control of a Nonholonomic Car-like Robot, in Robot Motion Planning and Control (Ed. J.-P. Laumond), Springer, 1998. (https://homepages.laas.fr/jpl/promotion/chap4.pdf)
Definition at line 72 of file simple_car.h.
|
default |
Default constructor.
|
inline |
Constructs model with given wheelbase.
Definition at line 99 of file simple_car.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Reimplemented in mpc_local_planner::SimpleCarFrontWheelDrivingModel.
Definition at line 108 of file simple_car.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Definition at line 105 of file simple_car.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Reimplemented in mpc_local_planner::SimpleCarFrontWheelDrivingModel.
Definition at line 102 of file simple_car.h.
|
inlineoverridevirtual |
Convert control vector to twist message.
Convert the control vector to a twist message (containing velocity information) if possible.
| [in] | u | Reference to the control vector [getInputDimension() x 1] |
| [out] | twist | Reference to the twist message |
Implements mpc_local_planner::RobotDynamicsInterface.
Definition at line 120 of file simple_car.h.
|
inline |
Get wheelbase.
Definition at line 135 of file simple_car.h.
|
inline |
Set wheelbase.
Definition at line 133 of file simple_car.h.
|
protected |
Definition at line 138 of file simple_car.h.