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

#include <VehicleAckermann.h>

Inheritance diagram for mvsim::DynamicsAckermann:
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 }
 
- Public Types inherited from mvsim::VehicleBase
using Ptr = std::shared_ptr< VehicleBase >
 
typedef std::vector< SensorBase::PtrTListSensors
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 

Public Member Functions

void computeFrontWheelAngles (const double desired_equiv_steer_ang, double &out_fl_ang, double &out_fr_ang) const
 
 DynamicsAckermann (World *parent)
 
double getMaxSteeringAngle () const
 
virtual mrpt::math::TTwist2D getVelocityLocalOdoEstimate () const override
 
void setMaxSteeringAngle (double val)
 
- Public Member Functions inherited from mvsim::VehicleBase
virtual void apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override
 
void clearLogs ()
 
virtual void create_multibody_system (b2World &world)
 
b2Fixtureget_fixture_chassis ()
 
const b2Fixtureget_fixture_chassis () const
 
std::vector< b2Fixture * > & get_fixture_wheels ()
 
const std::vector< b2Fixture * > & get_fixture_wheels () const
 
b2BodygetBox2DChassisBody ()
 
mrpt::math::TPoint2D getChassisCenterOfMass () const
 In local coordinates (this excludes the mass of wheels) More...
 
virtual double getChassisMass () const
 
const mrpt::math::TPolygon2DgetChassisShape () const
 
std::shared_ptr< CSVLoggergetLoggerPtr (std::string logger_name)
 
virtual float getMaxVehicleRadius () const
 
size_t getNumWheels () const
 
const TListSensorsgetSensors () const
 
TListSensorsgetSensors ()
 
size_t getVehicleIndex () const
 
const WheelgetWheelInfo (const size_t idx) const
 
WheelgetWheelInfo (const size_t idx)
 
void getWheelsVelocityLocal (std::vector< mrpt::math::TPoint2D > &vels, const mrpt::math::TTwist2D &veh_vel_local) const
 
void newLogSession ()
 
void poses_mutex_lock () override
 
void poses_mutex_unlock () override
 
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
 
- Public Member Functions inherited from mvsim::VisualObject
void getVisualModelBoundingBox (mrpt::math::TPoint3D &bbmin, mrpt::math::TPoint3D &bbmax) const
 
WorldgetWorldObject ()
 
const WorldgetWorldObject () const
 
virtual void guiUpdate (mrpt::opengl::COpenGLScene &scene)
 
void showBoundingBox (bool show)
 
 VisualObject (World *parent)
 
virtual ~VisualObject ()
 
- Public Member Functions inherited from mvsim::Simulable
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
const std::stringgetName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TTwist2D getTwist () const
 
const mrpt::math::TTwist2DgetVelocity () 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
 

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...
 
double m_max_steer_ang = mrpt::DEG2RAD(30)
 

Controllers

typedef ControllerBaseTempl< DynamicsAckermannControllerBase
 
typedef std::shared_ptr< ControllerBaseControllerBasePtr
 
const ControllerBasePtrgetController () const
 
ControllerBasePtrgetController ()
 
virtual ControllerBaseInterfacegetControllerInterface () 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...
 
b2Fixturem_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< Wheelm_wheels_info
 
- Protected Attributes inherited from mvsim::VisualObject
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glBoundingBox
 
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glCustomVisual
 
int32_t m_glCustomVisualId = -1
 
Worldm_world
 
- Protected Attributes inherited from mvsim::Simulable
std::string m_name
 

Detailed Description

Implementation of 4 wheels Ackermann-driven vehicles.

See also
class factory in VehicleBase::factory

Definition at line 21 of file VehicleAckermann.h.

Member Typedef Documentation

Virtual base for controllers of vehicles of type DynamicsAckermann

Definition at line 61 of file VehicleAckermann.h.

Definition at line 62 of file VehicleAckermann.h.

Member Enumeration Documentation

anonymous enum
Enumerator
WHEEL_RL 
WHEEL_RR 
WHEEL_FL 
WHEEL_FR 

Definition at line 26 of file VehicleAckermann.h.

Constructor & Destructor Documentation

DynamicsAckermann::DynamicsAckermann ( World parent)

Definition at line 23 of file VehicleAckermann.cpp.

Member Function Documentation

void DynamicsAckermann::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 200 of file VehicleAckermann.cpp.

void DynamicsAckermann::dynamics_load_params_from_xml ( const rapidxml::xml_node< char > *  xml_node)
overrideprotectedvirtual

The derived-class part of load_params_from_xml()

Implements mvsim::VehicleBase.

Definition at line 60 of file VehicleAckermann.cpp.

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

Definition at line 141 of file VehicleAckermann.h.

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

Definition at line 142 of file VehicleAckermann.h.

virtual ControllerBaseInterface* mvsim::DynamicsAckermann::getControllerInterface ( )
inlineoverridevirtual

Implements mvsim::VehicleBase.

Definition at line 143 of file VehicleAckermann.h.

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

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

Definition at line 37 of file VehicleAckermann.h.

mrpt::math::TTwist2D DynamicsAckermann::getVelocityLocalOdoEstimate ( ) const
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.

See also
getVelocityLocal()

Implements mvsim::VehicleBase.

Definition at line 226 of file VehicleAckermann.cpp.

void DynamicsAckermann::invoke_motor_controllers ( const TSimulContext context,
std::vector< double > &  out_force_per_wheel 
)
overrideprotectedvirtual

Implements mvsim::VehicleBase.

Definition at line 172 of file VehicleAckermann.cpp.

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

Definition at line 38 of file VehicleAckermann.h.

Member Data Documentation

ControllerBasePtr mvsim::DynamicsAckermann::m_controller
private

The installed controller.

Definition at line 171 of file VehicleAckermann.h.

double mvsim::DynamicsAckermann::m_max_steer_ang = mrpt::DEG2RAD(30)
private

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

Definition at line 174 of file VehicleAckermann.h.


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


mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:52