#include <VehicleDifferential.h>
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::Ptr > | TListSensors |
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) |
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 |
mrpt::poses::CPose2D | getCPose2D () const |
std::shared_ptr< CSVLogger > | getLoggerPtr (std::string logger_name) |
virtual float | getMaxVehicleRadius () const |
const std::string & | getName () const |
size_t | getNumWheels () const |
const mrpt::math::TPose3D & | getPose () const |
const TListSensors & | getSensors () const |
TListSensors & | getSensors () |
size_t | getVehicleIndex () const |
const vec3 & | getVelocity () const |
vec3 | getVelocityLocal () const |
const Wheel & | getWheelInfo (const size_t idx) const |
Wheel & | getWheelInfo (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 | |
World * | getWorldObject () |
const World * | getWorldObject () 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< DynamicsDifferential > | ControllerBase |
typedef std::shared_ptr< ControllerBase > | ControllerBasePtr |
const ControllerBasePtr & | getController () const |
ControllerBasePtr & | getController () |
virtual ControllerBaseInterface * | getControllerInterface () |
Additional Inherited Members | |
Static Public Member Functions inherited from mvsim::VehicleBase | |
static VehicleBase * | factory (World *parent, const rapidxml::xml_node< char > *xml_node) |
static VehicleBase * | factory (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 | |
World * | m_world |
Implementation of differential-driven vehicles.
Definition at line 22 of file VehicleDifferential.h.
Virtual base for controllers of vehicles of type DynamicsDifferential
Definition at line 48 of file VehicleDifferential.h.
typedef std::shared_ptr<ControllerBase> mvsim::DynamicsDifferential::ControllerBasePtr |
Definition at line 49 of file VehicleDifferential.h.
anonymous enum |
Enumerator | |
---|---|
WHEEL_L | |
WHEEL_R |
Definition at line 26 of file VehicleDifferential.h.
DynamicsDifferential::DynamicsDifferential | ( | World * | parent | ) |
Definition at line 22 of file VehicleDifferential.cpp.
|
protectedvirtual |
The derived-class part of load_params_from_xml()
Implements mvsim::VehicleBase.
Definition at line 47 of file VehicleDifferential.cpp.
|
inline |
Definition at line 107 of file VehicleDifferential.h.
|
inline |
Definition at line 108 of file VehicleDifferential.h.
|
inlinevirtual |
Implements mvsim::VehicleBase.
Definition at line 109 of file VehicleDifferential.h.
|
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.
Implements mvsim::VehicleBase.
Definition at line 149 of file VehicleDifferential.cpp.
|
protectedvirtual |
Implements mvsim::VehicleBase.
Definition at line 129 of file VehicleDifferential.cpp.
|
private |
The installed controller.
Definition at line 127 of file VehicleDifferential.h.