Classes | Public Types | Public Member Functions | Protected Member Functions | Private Attributes
mvsim::DynamicsAckermannDrivetrain Class Reference

#include <VehicleAckermann_Drivetrain.h>

Inheritance diagram for mvsim::DynamicsAckermannDrivetrain:
Inheritance graph
[legend]

List of all members.

Classes

class  ControllerFrontSteerPID
class  ControllerRawForces
class  ControllerTwistFrontSteerPID
struct  TControllerInput
struct  TControllerOutput

Public Types

enum  { WHEEL_RL = 0, WHEEL_RR = 1, WHEEL_FL = 2, WHEEL_FR = 3 }
enum  DifferentialType {
  DIFF_OPEN_FRONT = 0, DIFF_OPEN_REAR = 1, DIFF_OPEN_4WD = 2, DIFF_TORSEN_FRONT = 3,
  DIFF_TORSEN_REAR = 4, DIFF_TORSEN_4WD = 5, DIFF_MAX
}

Public Member Functions

void computeDiffTorqueSplit (const double w1, const double w2, const double diffBias, const double defaultSplitRatio, double &t1, double &t2)
void computeFrontWheelAngles (const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
 DynamicsAckermannDrivetrain (World *parent)
double getMaxSteeringAngle () const
virtual vec3 getVelocityLocalOdoEstimate () const
void setMaxSteeringAngle (double val)

Protected Member Functions

virtual void dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node)
virtual void invoke_motor_controllers (const TSimulContext &context, std::vector< double > &out_force_per_wheel)

Private Attributes

ControllerBasePtr m_controller
 The installed controller.
DifferentialType m_diff_type
 min turning radius
double m_FrontLRBias
double m_FrontLRSplit
double m_FrontRearBias
double m_FrontRearSplit
double m_max_steer_ang
double m_RearLRBias
double m_RearLRSplit

Controllers

typedef ControllerBaseTempl
< DynamicsAckermannDrivetrain
ControllerBase
typedef std::shared_ptr
< ControllerBase
ControllerBasePtr
const ControllerBasePtrgetController () const
ControllerBasePtrgetController ()
virtual ControllerBaseInterfacegetControllerInterface ()

Detailed Description

Implementation of 4 wheels Ackermann-driven vehicles with drivetrain As motor input of drivetrain acts controller torque. Differential model is based on observations of Torsen-like differentials work. http://www.flashoffroad.com/features/Torsen/Torsen_white_paper.pdf

See also:
class factory in VehicleBase::factory

Definition at line 29 of file VehicleAckermann_Drivetrain.h.


Member Typedef Documentation

Virtual base for controllers of vehicles of type DynamicsAckermannLSDiff

Definition at line 76 of file VehicleAckermann_Drivetrain.h.

Definition at line 77 of file VehicleAckermann_Drivetrain.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
WHEEL_RL 
WHEEL_RR 
WHEEL_FL 
WHEEL_FR 

Definition at line 34 of file VehicleAckermann_Drivetrain.h.

Enumerator:
DIFF_OPEN_FRONT 
DIFF_OPEN_REAR 
DIFF_OPEN_4WD 
DIFF_TORSEN_FRONT 
DIFF_TORSEN_REAR 
DIFF_TORSEN_4WD 
DIFF_MAX 

Definition at line 42 of file VehicleAckermann_Drivetrain.h.


Constructor & Destructor Documentation

Definition at line 23 of file VehicleAckermann_Drivetrain.cpp.


Member Function Documentation

void DynamicsAckermannDrivetrain::computeDiffTorqueSplit ( const double  w1,
const double  w2,
const double  diffBias,
const double  defaultSplitRatio,
double &  t1,
double &  t2 
)

Computes differential split for Torsen-like limited slip differentials.

Definition at line 386 of file VehicleAckermann_Drivetrain.cpp.

void DynamicsAckermannDrivetrain::computeFrontWheelAngles ( const double  desired_equiv_steer_ang,
double &  out_fl_ang,
double &  out_fr_ang 
) const

Computes the exact angles of the front wheels required to have an equivalent central steering angle. The method takes into account all wheels info & steering limits stored in the object.

Definition at line 361 of file VehicleAckermann_Drivetrain.cpp.

void DynamicsAckermannDrivetrain::dynamics_load_params_from_xml ( const rapidxml::xml_node< char > *  xml_node) [protected, virtual]

The derived-class part of load_params_from_xml()

Implements mvsim::VehicleBase.

Definition at line 73 of file VehicleAckermann_Drivetrain.cpp.

Definition at line 156 of file VehicleAckermann_Drivetrain.h.

Definition at line 157 of file VehicleAckermann_Drivetrain.h.

Implements mvsim::VehicleBase.

Definition at line 158 of file VehicleAckermann_Drivetrain.h.

The maximum steering angle (rad). Determines min turning radius

Definition at line 58 of file VehicleAckermann_Drivetrain.h.

Gets the current estimation of odometry-based velocity as reconstructed solely from wheels spinning velocities and geometry. This is the input of any realistic low-level controller onboard.

See also:
getVelocityLocal()

Implements mvsim::VehicleBase.

Definition at line 418 of file VehicleAckermann_Drivetrain.cpp.

void DynamicsAckermannDrivetrain::invoke_motor_controllers ( const TSimulContext context,
std::vector< double > &  out_force_per_wheel 
) [protected, virtual]

Implements mvsim::VehicleBase.

Definition at line 228 of file VehicleAckermann_Drivetrain.cpp.

Definition at line 59 of file VehicleAckermann_Drivetrain.h.


Member Data Documentation

The installed controller.

Definition at line 191 of file VehicleAckermann_Drivetrain.h.

min turning radius

Definition at line 196 of file VehicleAckermann_Drivetrain.h.

Definition at line 203 of file VehicleAckermann_Drivetrain.h.

Definition at line 199 of file VehicleAckermann_Drivetrain.h.

Definition at line 202 of file VehicleAckermann_Drivetrain.h.

Definition at line 198 of file VehicleAckermann_Drivetrain.h.

The maximum steering angle (rad). Determines

Definition at line 193 of file VehicleAckermann_Drivetrain.h.

Definition at line 204 of file VehicleAckermann_Drivetrain.h.

Definition at line 200 of file VehicleAckermann_Drivetrain.h.


The documentation for this class was generated from the following files:


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:49