#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 } |
![]() | |
using | Ptr = std::shared_ptr< VehicleBase > |
![]() | |
using | Ptr = std::shared_ptr< Simulable > |
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 mrpt::math::TTwist2D | getVelocityLocalOdoEstimate () const override |
void | setMaxSteeringAngle (double val) |
![]() | |
virtual void | apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override |
void | chassisAndWheelsVisible (bool visible) |
void | clearLogs () |
virtual void | create_multibody_system (b2World &world) |
void | freeOpenGLResources () override |
b2Fixture * | get_fixture_chassis () |
const b2Fixture * | get_fixture_chassis () const |
std::vector< b2Fixture * > & | get_fixture_wheels () |
const std::vector< b2Fixture * > & | get_fixture_wheels () const |
b2Body * | getBox2DChassisBody () |
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 |
std::shared_ptr< CSVLogger > | getLoggerPtr (std::string logger_name) |
virtual float | getMaxVehicleRadius () const |
size_t | getNumWheels () const |
const TListSensors & | getSensors () const |
TListSensors & | getSensors () |
size_t | getVehicleIndex () const |
const Wheel & | getWheelInfo (const size_t idx) const |
Wheel & | getWheelInfo (const size_t idx) |
std::vector< mrpt::math::TVector2D > | getWheelsVelocityLocal (const mrpt::math::TTwist2D &veh_vel_local) const |
void | newLogSession () |
void | registerOnServer (mvsim::Client &c) override |
void | setRecording (bool record) |
void | setVehicleIndex (size_t idx) |
virtual void | simul_post_timestep (const TSimulContext &context) override |
virtual void | simul_pre_timestep (const TSimulContext &context) override |
![]() | |
const std::optional< Shape2p5 > & | collisionShape () const |
void | customVisualVisible (const bool visible) |
bool | customVisualVisible () const |
virtual void | guiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical) |
World * | parent () |
const World * | parent () const |
void | showCollisionShape (bool show) |
VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true) | |
virtual | ~VisualObject () |
![]() | |
const b2Body * | b2d_body () const |
b2Body * | b2d_body () |
mrpt::poses::CPose2D | getCPose2D () const |
Alternative to getPose() More... | |
mrpt::poses::CPose3D | getCPose3D () const |
Alternative to getPose() More... | |
mrpt::math::TVector3D | getLinearAcceleration () const |
const std::string & | getName () const |
mrpt::math::TPose3D | getPose () const |
mrpt::math::TPose3D | getPoseNoLock () const |
No thread-safe version. Used internally only. More... | |
World * | getSimulableWorldObject () |
const World * | getSimulableWorldObject () const |
mrpt::math::TTwist2D | getTwist () const |
mrpt::math::TTwist2D | getVelocityLocal () const |
bool | hadCollision () const |
bool | isInCollision () const |
void | resetCollisionFlag () |
void | setName (const std::string &s) |
void | setPose (const mrpt::math::TPose3D &p) const |
void | setTwist (const mrpt::math::TTwist2D &dq) const |
Simulable (World *parent) | |
Protected Member Functions | |
virtual void | dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node) override |
virtual std::vector< double > | invoke_motor_controllers (const TSimulContext &context) override |
![]() | |
virtual void | initLoggers () |
virtual void | internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override |
virtual void | invoke_motor_controllers_post_step ([[maybe_unused]] const TSimulContext &context) |
VisualObject * | meAsVisualObject () override |
void | updateMaxRadiusFromPoly () |
VehicleBase (World *parent, size_t nWheels) | |
virtual void | writeLogStrings () |
![]() | |
void | addCustomVisualization (const mrpt::opengl::CRenderizable::Ptr &glModel, const mrpt::poses::CPose3D &modelPose={}, const float modelScale=1.0f, const std::string &modelName="group", const std::optional< std::string > &modelURI=std::nullopt, const bool initialShowBoundingBox=false) |
bool | parseVisual (const rapidxml::xml_node< char > &rootNode) |
Returns true if there is at least one <visual>...</visual> entry. More... | |
bool | parseVisual (const JointXMLnode<> &rootNode) |
void | setCollisionShape (const Shape2p5 &cs) |
Private Attributes | |
ControllerBase::Ptr | controller_ |
The installed controller. More... | |
DifferentialType | diff_type_ |
min turning radius More... | |
double | FrontLRBias_ |
double | FrontLRSplit_ |
double | FrontRearBias_ |
double | FrontRearSplit_ |
double | max_steer_ang_ |
double | RearLRBias_ |
double | RearLRSplit_ |
Controllers | |
using | ControllerBase = ControllerBaseTempl< DynamicsAckermannDrivetrain > |
const ControllerBase::Ptr & | getController () const |
ControllerBase::Ptr & | getController () |
virtual ControllerBaseInterface * | getControllerInterface () override |
Additional Inherited Members | |
![]() | |
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 void | FreeOpenGLResources () |
![]() | |
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" |
![]() | |
static double | GeometryEpsilon = 1e-3 |
![]() | |
mrpt::img::TColor | chassis_color_ {0xff, 0x00, 0x00} |
mrpt::math::TPoint2D | chassis_com_ {0, 0} |
double | chassis_mass_ = 15.0 |
mrpt::math::TPolygon2D | chassis_poly_ |
double | chassis_z_max_ = 0.6 |
double | chassis_z_min_ = 0.05 |
b2Fixture * | fixture_chassis_ |
Created at. More... | |
std::vector< b2Fixture * > | fixture_wheels_ |
FrictionBasePtr | friction_ |
std::string | log_path_ |
std::map< std::string, std::shared_ptr< CSVLogger > > | loggers_ |
double | maxRadius_ = 0.1 |
TListSensors | sensors_ |
Sensors aboard. More... | |
size_t | vehicle_index_ = 0 |
std::deque< Wheel > | wheels_info_ |
![]() | |
std::shared_ptr< mrpt::opengl::CSetOfObjects > | glCollision_ |
std::shared_ptr< mrpt::opengl::CSetOfObjects > | glCustomVisual_ |
int32_t | glCustomVisualId_ = -1 |
const bool | insertCustomVizIntoPhysical_ = true |
const bool | insertCustomVizIntoViz_ = true |
World * | world_ |
![]() | |
std::string | 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.
using mvsim::DynamicsAckermannDrivetrain::ControllerBase = ControllerBaseTempl<DynamicsAckermannDrivetrain> |
Virtual base for controllers of vehicles of type DynamicsAckermannLSDiff
Definition at line 73 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 390 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 365 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 149 of file VehicleAckermann_Drivetrain.h.
|
inline |
Definition at line 150 of file VehicleAckermann_Drivetrain.h.
|
inlineoverridevirtual |
Implements mvsim::VehicleBase.
Definition at line 151 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 421 of file VehicleAckermann_Drivetrain.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VehicleBase.
Definition at line 231 of file VehicleAckermann_Drivetrain.cpp.
|
inline |
Definition at line 56 of file VehicleAckermann_Drivetrain.h.
|
private |
The installed controller.
Definition at line 184 of file VehicleAckermann_Drivetrain.h.
|
private |
min turning radius
Definition at line 189 of file VehicleAckermann_Drivetrain.h.
|
private |
Definition at line 196 of file VehicleAckermann_Drivetrain.h.
|
private |
Definition at line 192 of file VehicleAckermann_Drivetrain.h.
|
private |
Definition at line 195 of file VehicleAckermann_Drivetrain.h.
|
private |
Definition at line 191 of file VehicleAckermann_Drivetrain.h.
|
private |
The maximum steering angle (rad). Determines
Definition at line 186 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.