#include <VehicleAckermann_Drivetrain.h>

| 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 | |
| using | Ptr = std::shared_ptr< VehicleBase > | 
| typedef std::vector< SensorBase::Ptr > | TListSensors | 
|  Public Types inherited from mvsim::Simulable | |
| using | Ptr = std::shared_ptr< Simulable > | 
| Protected Member Functions | |
| virtual void | dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node) override | 
| virtual void | invoke_motor_controllers (const TSimulContext &context, std::vector< double > &out_force_per_wheel) override | 
|  Protected Member Functions inherited from mvsim::VehicleBase | |
| virtual void | initLoggers () | 
| virtual mrpt::poses::CPose3D | internalGuiGetVisualPose () override | 
| virtual void | internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override | 
| void | updateMaxRadiusFromPoly () | 
| excludes the mass of wheels)  More... | |
| VehicleBase (World *parent, size_t nWheels) | |
| virtual void | writeLogStrings () | 
|  Protected Member Functions inherited from mvsim::VisualObject | |
| bool | parseVisual (const rapidxml::xml_node< char > *visual_node) | 
| 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< DynamicsAckermannDrivetrain > | ControllerBase | 
| typedef std::shared_ptr< ControllerBase > | ControllerBasePtr | 
| const ControllerBasePtr & | getController () const | 
| ControllerBasePtr & | getController () | 
| virtual ControllerBaseInterface * | getControllerInterface () override | 
| Additional Inherited Members | |
|  Static Public Member Functions inherited from mvsim::VehicleBase | |
| static Ptr | factory (World *parent, const rapidxml::xml_node< char > *xml_node) | 
| static Ptr | factory (World *parent, const std::string &xml_text) | 
| static void | register_vehicle_class (const rapidxml::xml_node< char > *xml_node) | 
|  Static Public Attributes inherited from mvsim::VehicleBase | |
| static constexpr char | DL_TIMESTAMP [] = "timestamp" | 
| static constexpr char | LOGGER_POSE [] = "logger_pose" | 
| static constexpr char | LOGGER_WHEEL [] = "logger_wheel" | 
| static constexpr char | PL_DQ_X [] = "dQx" | 
| static constexpr char | PL_DQ_Y [] = "dQy" | 
| static constexpr char | PL_DQ_Z [] = "dQz" | 
| static constexpr char | PL_Q_PITCH [] = "Qpitch" | 
| static constexpr char | PL_Q_ROLL [] = "Qroll" | 
| static constexpr char | PL_Q_X [] = "Qx" | 
| static constexpr char | PL_Q_Y [] = "Qy" | 
| static constexpr char | PL_Q_YAW [] = "Qyaw" | 
| static constexpr char | PL_Q_Z [] = "Qz" | 
| static constexpr char | WL_FRIC_X [] = "friction_x" | 
| static constexpr char | WL_FRIC_Y [] = "friction_y" | 
| static constexpr char | WL_TORQUE [] = "torque" | 
| static constexpr char | WL_VEL_X [] = "velocity_x" | 
| static constexpr char | WL_VEL_Y [] = "velocity_y" | 
| static constexpr char | WL_WEIGHT [] = "weight" | 
|  Protected Attributes inherited from mvsim::VehicleBase | |
| mrpt::img::TColor | m_chassis_color | 
| mrpt::math::TPoint2D | m_chassis_com | 
| double | m_chassis_mass | 
| mrpt::math::TPolygon2D | m_chassis_poly | 
| double | m_chassis_z_max | 
| double | m_chassis_z_min | 
| each change via updateMaxRadiusFromPoly()  More... | |
| b2Fixture * | m_fixture_chassis | 
| Created at.  More... | |
| std::vector< b2Fixture * > | m_fixture_wheels | 
| FrictionBasePtr | m_friction | 
| std::string | m_log_path | 
| std::map< std::string, std::shared_ptr< CSVLogger > > | m_loggers | 
| double | m_max_radius | 
| TListSensors | m_sensors | 
| Sensors aboard.  More... | |
| std::vector< double > | m_torque_per_wheel | 
| size_t | m_vehicle_index | 
| std::vector< Wheel > | m_wheels_info | 
|  Protected Attributes inherited from mvsim::VisualObject | |
| std::shared_ptr< mrpt::opengl::CSetOfObjects > | m_glBoundingBox | 
| std::shared_ptr< mrpt::opengl::CSetOfObjects > | m_glCustomVisual | 
| int32_t | m_glCustomVisualId = -1 | 
| World * | m_world | 
|  Protected Attributes inherited from mvsim::Simulable | |
| std::string | m_name | 
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
Definition at line 26 of file VehicleAckermann_Drivetrain.h.
| typedef ControllerBaseTempl<DynamicsAckermannDrivetrain> mvsim::DynamicsAckermannDrivetrain::ControllerBase | 
Virtual base for controllers of vehicles of type DynamicsAckermannLSDiff
Definition at line 73 of file VehicleAckermann_Drivetrain.h.
| typedef std::shared_ptr<ControllerBase> mvsim::DynamicsAckermannDrivetrain::ControllerBasePtr | 
Definition at line 74 of file VehicleAckermann_Drivetrain.h.
| anonymous enum | 
| Enumerator | |
|---|---|
| WHEEL_RL | |
| WHEEL_RR | |
| WHEEL_FL | |
| WHEEL_FR | |
Definition at line 31 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 39 of file VehicleAckermann_Drivetrain.h.
| DynamicsAckermannDrivetrain::DynamicsAckermannDrivetrain | ( | World * | parent | ) | 
Definition at line 23 of file VehicleAckermann_Drivetrain.cpp.
| 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 384 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 359 of file VehicleAckermann_Drivetrain.cpp.
| 
 | overrideprotectedvirtual | 
The derived-class part of load_params_from_xml()
Implements mvsim::VehicleBase.
Definition at line 72 of file VehicleAckermann_Drivetrain.cpp.
| 
 | inline | 
Definition at line 150 of file VehicleAckermann_Drivetrain.h.
| 
 | inline | 
Definition at line 151 of file VehicleAckermann_Drivetrain.h.
| 
 | inlineoverridevirtual | 
Implements mvsim::VehicleBase.
Definition at line 152 of file VehicleAckermann_Drivetrain.h.
| 
 | inline | 
The maximum steering angle (rad). Determines min turning radius
Definition at line 55 of file VehicleAckermann_Drivetrain.h.
| 
 | overridevirtual | 
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.
Implements mvsim::VehicleBase.
Definition at line 415 of file VehicleAckermann_Drivetrain.cpp.
| 
 | overrideprotectedvirtual | 
Implements mvsim::VehicleBase.
Definition at line 226 of file VehicleAckermann_Drivetrain.cpp.
| 
 | inline | 
Definition at line 56 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
The installed controller.
Definition at line 186 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
min turning radius
Definition at line 191 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 198 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 194 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 197 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 193 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
The maximum steering angle (rad). Determines
Definition at line 188 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 199 of file VehicleAckermann_Drivetrain.h.
| 
 | private | 
Definition at line 195 of file VehicleAckermann_Drivetrain.h.