Kinematic Bicycle Model with Velocity Input. More...
#include <kinematic_bicycle_model.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 |
double | getLengthFront () const |
Get length between COG and front axle. More... | |
double | getLengthRear () const |
Get length between COG and rear axle. More... | |
bool | getTwistFromControl (const Eigen::Ref< const Eigen::VectorXd > &u, geometry_msgs::Twist &twist) const override |
Convert control vector to twist message. More... | |
KinematicBicycleModelVelocityInput ()=default | |
Default constructor. More... | |
KinematicBicycleModelVelocityInput (double lr, double lf) | |
Constructs model with given wheelbase. More... | |
void | setParameters (double lr, double lf) |
Set parameters. More... | |
![]() | |
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... | |
![]() | |
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 () |
![]() | |
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 | _lf = 1.0 |
double | _lr = 1.0 |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< BaseRobotSE2 > |
![]() | |
using | Ptr = std::shared_ptr< RobotDynamicsInterface > |
![]() | |
typedef Eigen::VectorXd | ControlVector |
typedef std::shared_ptr< SystemDynamicsInterface > | Ptr |
typedef Eigen::VectorXd | StateVector |
Kinematic Bicycle Model with Velocity Input.
This class implements the dynamics for a kinematic bicycle model. Note, in this model the robot coordinate system is located at the center of gravity which is between the rear and the front axle. In case you want to define the coordinate system at the rear axle, please refer to the simplified equations simple_car.h (SimpleCarModel).
[1] R. Rajamani, Vehicle Dynamics and Control, Springer, 2012. [2] J. Kong et al., Kinematic and Dynamic Vehicle Models for Autonomous Driving Control Design, IV, 2015.
Definition at line 69 of file kinematic_bicycle_model.h.
|
default |
Default constructor.
|
inline |
Constructs model with given wheelbase.
Definition at line 96 of file kinematic_bicycle_model.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Definition at line 105 of file kinematic_bicycle_model.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Definition at line 102 of file kinematic_bicycle_model.h.
|
inlineoverridevirtual |
Implements mpc_local_planner::BaseRobotSE2.
Definition at line 99 of file kinematic_bicycle_model.h.
|
inline |
Get length between COG and front axle.
Definition at line 139 of file kinematic_bicycle_model.h.
|
inline |
Get length between COG and rear axle.
Definition at line 141 of file kinematic_bicycle_model.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 kinematic_bicycle_model.h.
|
inline |
Set parameters.
Definition at line 133 of file kinematic_bicycle_model.h.
|
protected |
Definition at line 145 of file kinematic_bicycle_model.h.
|
protected |
Definition at line 144 of file kinematic_bicycle_model.h.