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

#include <VehicleDifferential.h>

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

Classes

class  ControllerRawForces
 
class  ControllerTwistPID
 
struct  TControllerInput
 
struct  TControllerOutput
 

Public Types

enum  { WHEEL_L = 0, WHEEL_R = 1 }
 
- Public Types inherited from mvsim::VehicleBase
typedef std::vector< SensorBase::PtrTListSensors
 

Public Member Functions

 DynamicsDifferential (World *parent)
 
virtual vec3 getVelocityLocalOdoEstimate () const
 
- 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...
 

Controllers

typedef ControllerBaseTempl< DynamicsDifferentialControllerBase
 
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 differential-driven vehicles.

See also
class factory in VehicleBase::factory

Definition at line 22 of file VehicleDifferential.h.

Member Typedef Documentation

Virtual base for controllers of vehicles of type DynamicsDifferential

Definition at line 48 of file VehicleDifferential.h.

Definition at line 49 of file VehicleDifferential.h.

Member Enumeration Documentation

anonymous enum
Enumerator
WHEEL_L 
WHEEL_R 

Definition at line 26 of file VehicleDifferential.h.

Constructor & Destructor Documentation

DynamicsDifferential::DynamicsDifferential ( World parent)

Definition at line 22 of file VehicleDifferential.cpp.

Member Function Documentation

void DynamicsDifferential::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 47 of file VehicleDifferential.cpp.

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

Definition at line 107 of file VehicleDifferential.h.

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

Definition at line 108 of file VehicleDifferential.h.

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

Implements mvsim::VehicleBase.

Definition at line 109 of file VehicleDifferential.h.

vec3 DynamicsDifferential::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 149 of file VehicleDifferential.cpp.

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

Implements mvsim::VehicleBase.

Definition at line 129 of file VehicleDifferential.cpp.

Member Data Documentation

ControllerBasePtr mvsim::DynamicsDifferential::m_controller
private

The installed controller.

Definition at line 127 of file VehicleDifferential.h.


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


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