#include <VehicleBase.h>
Public Types | |
using | Ptr = std::shared_ptr< VehicleBase > |
typedef std::vector< SensorBase::Ptr > | TListSensors |
Public Types inherited from mvsim::Simulable | |
using | Ptr = std::shared_ptr< Simulable > |
Static Public Member Functions | |
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 | |
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 Member Functions | |
virtual void | dynamics_load_params_from_xml (const rapidxml::xml_node< char > *xml_node)=0 |
virtual void | initLoggers () |
virtual mrpt::poses::CPose3D | internalGuiGetVisualPose () override |
virtual void | internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override |
virtual void | invoke_motor_controllers (const TSimulContext &context, std::vector< double > &out_force_per_wheel)=0 |
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) |
Protected Attributes | |
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 |
Private Member Functions | |
void | internal_internalGuiUpdate_forces (mrpt::opengl::COpenGLScene &scene) |
void | internal_internalGuiUpdate_sensors (mrpt::opengl::COpenGLScene &scene) |
Private Attributes | |
std::vector< mrpt::math::TSegment3D > | m_force_segments_for_rendering |
std::mutex | m_force_segments_for_rendering_cs |
mrpt::opengl::CSetOfObjects::Ptr | m_gl_chassis |
mrpt::opengl::CSetOfLines::Ptr | m_gl_forces |
std::vector< mrpt::opengl::CSetOfObjects::Ptr > | m_gl_wheels |
std::mutex | m_gui_mtx |
Virtual base class for each vehicle "actor" in the simulation. Derived classes implements different dynamical models (Differential, Ackermann,...)
Definition at line 41 of file VehicleBase.h.
using mvsim::VehicleBase::Ptr = std::shared_ptr<VehicleBase> |
Definition at line 44 of file VehicleBase.h.
typedef std::vector<SensorBase::Ptr> mvsim::VehicleBase::TListSensors |
Definition at line 102 of file VehicleBase.h.
|
protected |
Definition at line 78 of file VehicleBase.cpp.
|
overridevirtual |
Override to register external forces exerted by other WorldElements. Force is (fx,fy) in global coordinates. Application point is (local_ptx,local_pty) in the body local frame
Reimplemented from mvsim::Simulable.
Definition at line 763 of file VehicleBase.cpp.
|
inline |
Definition at line 126 of file VehicleBase.h.
Create bodies, fixtures, etc. for the dynamical simulation. May be overrided by derived classes
Create bodies, fixtures, etc. for the dynamical simulation
Definition at line 577 of file VehicleBase.cpp.
|
protectedpure virtual |
Parse node <dynamics>: The derived-class part of load_params_from_xml(), also called in factory(). Includes parsing the <controller></controller> block.
Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.
|
static |
Class factory: Creates a vehicle from XML description of type "<vehicle>...</vehicle>".
Definition at line 124 of file VehicleBase.cpp.
|
static |
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
Definition at line 339 of file VehicleBase.cpp.
|
inline |
Definition at line 139 of file VehicleBase.h.
Definition at line 141 of file VehicleBase.h.
|
inline |
Definition at line 140 of file VehicleBase.h.
Definition at line 142 of file VehicleBase.h.
|
inline |
Definition at line 77 of file VehicleBase.h.
|
inline |
In local coordinates (this excludes the mass of wheels)
Definition at line 78 of file VehicleBase.h.
|
inlinevirtual |
Get the overall vehicle mass, excluding wheels.
Definition at line 76 of file VehicleBase.h.
|
inline |
Get the 2D shape of the vehicle chassis, as set from the config file (only used for collision detection)
Definition at line 113 of file VehicleBase.h.
|
pure virtual |
Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.
|
inline |
Definition at line 106 of file VehicleBase.h.
|
inlinevirtual |
Get (an approximation of) the max radius of the vehicle, from its point of reference (in meters)
Definition at line 74 of file VehicleBase.h.
|
inline |
Definition at line 83 of file VehicleBase.h.
|
inline |
Definition at line 104 of file VehicleBase.h.
|
inline |
Definition at line 105 of file VehicleBase.h.
|
inline |
Get the vehicle index in the World
Definition at line 121 of file VehicleBase.h.
|
pure 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.
Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.
Definition at line 84 of file VehicleBase.h.
Definition at line 88 of file VehicleBase.h.
void VehicleBase::getWheelsVelocityLocal | ( | std::vector< mrpt::math::TPoint2D > & | vels, |
const mrpt::math::TTwist2D & | veh_vel_local | ||
) | const |
Current velocity of each wheel's center point (in local coords). Call with veh_vel_local=getVelocityLocal() for ground-truth.
Last time-step velocity of each wheel's center point (in local coords)
Definition at line 515 of file VehicleBase.cpp.
|
protectedvirtual |
Definition at line 714 of file VehicleBase.cpp.
|
private |
Definition at line 548 of file VehicleBase.cpp.
|
private |
(depending on derived class). Size set at constructor.
Definition at line 542 of file VehicleBase.cpp.
|
overrideprotectedvirtual |
Reimplemented from mvsim::VisualObject.
Definition at line 537 of file VehicleBase.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
Definition at line 654 of file VehicleBase.cpp.
|
protectedpure virtual |
Implemented in mvsim::DynamicsAckermannDrivetrain, mvsim::DynamicsAckermann, and mvsim::DynamicsDifferential.
|
inline |
Definition at line 130 of file VehicleBase.h.
|
inlineoverridevirtual |
Implements mvsim::Simulable.
Definition at line 57 of file VehicleBase.h.
|
inlineoverridevirtual |
Implements mvsim::Simulable.
Definition at line 58 of file VehicleBase.h.
|
static |
Register a new class of vehicles from XML description of type "<vehicle:class name='name'>...</vehicle:class>".
Definition at line 101 of file VehicleBase.cpp.
|
overridevirtual |
Reimplemented from mvsim::Simulable.
Definition at line 772 of file VehicleBase.cpp.
|
inline |
Definition at line 122 of file VehicleBase.h.
|
inline |
Set the vehicle index in the World
Definition at line 119 of file VehicleBase.h.
|
overridevirtual |
Override to do any required process right after the integration of dynamic equations for each timestep
Reimplemented from mvsim::Simulable.
Definition at line 468 of file VehicleBase.cpp.
|
overridevirtual |
Process right before the integration of dynamic equations for each timestep: set action forces from motors, update friction models, etc.
Reimplemented from mvsim::Simulable.
Definition at line 363 of file VehicleBase.cpp.
|
protected |
excludes the mass of wheels)
Definition at line 564 of file VehicleBase.cpp.
|
protectedvirtual |
Definition at line 754 of file VehicleBase.cpp.
|
static |
Definition at line 223 of file VehicleBase.h.
|
static |
Definition at line 224 of file VehicleBase.h.
|
static |
Definition at line 225 of file VehicleBase.h.
|
protected |
Definition at line 189 of file VehicleBase.h.
|
protected |
In local coordinates (this
Definition at line 191 of file VehicleBase.h.
|
protected |
Definition at line 184 of file VehicleBase.h.
|
protected |
Definition at line 185 of file VehicleBase.h.
|
protected |
Definition at line 188 of file VehicleBase.h.
|
protected |
each change via updateMaxRadiusFromPoly()
Definition at line 188 of file VehicleBase.h.
|
protected |
Created at.
upon construction. Derived classes must define the order of the wheels, e.g. [0]=rear left, etc.
Definition at line 203 of file VehicleBase.h.
|
protected |
[0]:rear-left, etc.
Definition at line 204 of file VehicleBase.h.
|
private |
Definition at line 218 of file VehicleBase.h.
|
private |
Definition at line 217 of file VehicleBase.h.
|
protected |
Instance of friction model for the vehicle-to-ground interaction.
Definition at line 176 of file VehicleBase.h.
|
private |
Definition at line 214 of file VehicleBase.h.
|
private |
Definition at line 216 of file VehicleBase.h.
|
private |
Definition at line 215 of file VehicleBase.h.
|
private |
Definition at line 220 of file VehicleBase.h.
|
protected |
Definition at line 149 of file VehicleBase.h.
|
protected |
Definition at line 148 of file VehicleBase.h.
|
protected |
Automatically computed from m_chassis_poly upon
Definition at line 186 of file VehicleBase.h.
|
protected |
Sensors aboard.
Definition at line 178 of file VehicleBase.h.
|
protected |
Updated in simul_pre_timestep()
Definition at line 181 of file VehicleBase.h.
|
protected |
user-supplied index number: must be set/get'ed with setVehicleIndex() getVehicleIndex() (default=0)
Definition at line 173 of file VehicleBase.h.
|
protected |
The fixed size of this vector is set
Definition at line 197 of file VehicleBase.h.
|
static |
Definition at line 233 of file VehicleBase.h.
|
static |
Definition at line 234 of file VehicleBase.h.
|
static |
Definition at line 235 of file VehicleBase.h.
|
static |
Definition at line 231 of file VehicleBase.h.
|
static |
Definition at line 232 of file VehicleBase.h.
|
static |
Definition at line 227 of file VehicleBase.h.
|
static |
Definition at line 228 of file VehicleBase.h.
|
static |
Definition at line 230 of file VehicleBase.h.
|
static |
Definition at line 229 of file VehicleBase.h.
|
static |
Definition at line 241 of file VehicleBase.h.
|
static |
Definition at line 242 of file VehicleBase.h.
|
static |
Definition at line 237 of file VehicleBase.h.
|
static |
Definition at line 239 of file VehicleBase.h.
|
static |
Definition at line 240 of file VehicleBase.h.
|
static |
Definition at line 238 of file VehicleBase.h.