Classes | Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
mvsim::DynamicsAckermannDrivetrain Class Reference

#include <VehicleAckermann_Drivetrain.h>

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

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 Types inherited from mvsim::VehicleBase
typedef std::vector< SensorBase::PtrTListSensors
 

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)
 
- Public Member Functions inherited from mvsim::VehicleBase
virtual void apply_force (double fx, double fy, double local_ptx=0.0, double local_pty=0.0)
 
void clearLogs ()
 
virtual void create_multibody_system (b2World *world)
 
b2BodygetBox2DChassisBody ()
 
mrpt::math::TPoint2D getChassisCenterOfMass () const
 In local coordinates (this excludes the mass of wheels) More...
 
virtual double getChassisMass () const
 
const mrpt::math::TPolygon2D & getChassisShape () const
 
mrpt::poses::CPose2D getCPose2D () const
 
std::shared_ptr< CSVLoggergetLoggerPtr (std::string logger_name)
 
virtual float getMaxVehicleRadius () const
 
const std::string & getName () const
 
size_t getNumWheels () const
 
const mrpt::math::TPose3D & getPose () const
 
const TListSensorsgetSensors () const
 
TListSensorsgetSensors ()
 
size_t getVehicleIndex () const
 
const vec3getVelocity () const
 
vec3 getVelocityLocal () const
 
const WheelgetWheelInfo (const size_t idx) const
 
WheelgetWheelInfo (const size_t idx)
 
void getWheelsVelocityLocal (std::vector< mrpt::math::TPoint2D > &vels, const vec3 &veh_vel_local) const
 
virtual void gui_update (mrpt::opengl::COpenGLScene &scene)
 
void newLogSession ()
 
void setPose (const mrpt::math::TPose3D &p) const
 
void setRecording (bool record)
 
void setVehicleIndex (size_t idx)
 
virtual void simul_post_timestep (const TSimulContext &context)
 
void simul_post_timestep_common (const TSimulContext &context)
 
virtual void simul_pre_timestep (const TSimulContext &context)
 
- Public Member Functions inherited from mvsim::VisualObject
WorldgetWorldObject ()
 
const WorldgetWorldObject () const
 
 VisualObject (World *parent)
 
virtual ~VisualObject ()
 

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)
 
- Protected Member Functions inherited from mvsim::VehicleBase
void gui_update_common (mrpt::opengl::COpenGLScene &scene, bool defaultVehicleBody=true)
 
virtual void initLoggers ()
 
 VehicleBase (World *parent, size_t nWheels)
 
virtual void writeLogStrings ()
 

Private Attributes

ControllerBasePtr m_controller
 The installed controller. More...
 
DifferentialType m_diff_type
 min turning radius More...
 
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< DynamicsAckermannDrivetrainControllerBase
 
typedef std::shared_ptr< ControllerBaseControllerBasePtr
 
const ControllerBasePtrgetController () const
 
ControllerBasePtrgetController ()
 
virtual ControllerBaseInterfacegetControllerInterface ()
 

Additional Inherited Members

- Static Public Member Functions inherited from mvsim::VehicleBase
static VehicleBasefactory (World *parent, const rapidxml::xml_node< char > *xml_node)
 
static VehicleBasefactory (World *parent, const std::string &xml_text)
 
static void register_vehicle_class (const rapidxml::xml_node< char > *xml_node)
 
- Protected Attributes inherited from mvsim::VehicleBase
std::string m_log_path
 
std::map< std::string, std::shared_ptr< CSVLogger > > m_loggers
 
std::string m_name
 User-supplied name of the vehicle (e.g. "r1", "veh1") More...
 
size_t m_vehicle_index
 
- Protected Attributes inherited from mvsim::VisualObject
Worldm_world
 

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

  \sa class factory in VehicleBase::factory

Definition at line 41 of file VehicleAckermann_Drivetrain.h.

Member Typedef Documentation

Virtual base for controllers of vehicles of type DynamicsAckermannLSDiff

Definition at line 88 of file VehicleAckermann_Drivetrain.h.

Definition at line 89 of file VehicleAckermann_Drivetrain.h.

Member Enumeration Documentation

anonymous enum
Enumerator
WHEEL_RL 
WHEEL_RR 
WHEEL_FL 
WHEEL_FR 

Definition at line 46 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 54 of file VehicleAckermann_Drivetrain.h.

Constructor & Destructor Documentation

DynamicsAckermannDrivetrain::DynamicsAckermannDrivetrain ( World parent)

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)
protectedvirtual

The derived-class part of load_params_from_xml()

Implements mvsim::VehicleBase.

Definition at line 73 of file VehicleAckermann_Drivetrain.cpp.

const ControllerBasePtr& mvsim::DynamicsAckermannDrivetrain::getController ( ) const
inline

Definition at line 168 of file VehicleAckermann_Drivetrain.h.

ControllerBasePtr& mvsim::DynamicsAckermannDrivetrain::getController ( )
inline

Definition at line 169 of file VehicleAckermann_Drivetrain.h.

virtual ControllerBaseInterface* mvsim::DynamicsAckermannDrivetrain::getControllerInterface ( )
inlinevirtual

Implements mvsim::VehicleBase.

Definition at line 170 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::getMaxSteeringAngle ( ) const
inline

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

Definition at line 70 of file VehicleAckermann_Drivetrain.h.

vec3 DynamicsAckermannDrivetrain::getVelocityLocalOdoEstimate ( ) const
virtual

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 
)
protectedvirtual

Implements mvsim::VehicleBase.

Definition at line 228 of file VehicleAckermann_Drivetrain.cpp.

void mvsim::DynamicsAckermannDrivetrain::setMaxSteeringAngle ( double  val)
inline

Definition at line 71 of file VehicleAckermann_Drivetrain.h.

Member Data Documentation

ControllerBasePtr mvsim::DynamicsAckermannDrivetrain::m_controller
private

The installed controller.

Definition at line 203 of file VehicleAckermann_Drivetrain.h.

DifferentialType mvsim::DynamicsAckermannDrivetrain::m_diff_type
private

min turning radius

Definition at line 208 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_FrontLRBias
private

Definition at line 215 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_FrontLRSplit
private

Definition at line 211 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_FrontRearBias
private

Definition at line 214 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_FrontRearSplit
private

Definition at line 210 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_max_steer_ang
private

The maximum steering angle (rad). Determines

Definition at line 205 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_RearLRBias
private

Definition at line 216 of file VehicleAckermann_Drivetrain.h.

double mvsim::DynamicsAckermannDrivetrain::m_RearLRSplit
private

Definition at line 212 of file VehicleAckermann_Drivetrain.h.


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


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 19:36:41