#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 | |
using | Ptr = std::shared_ptr< VehicleBase > |
typedef std::vector< SensorBase::Ptr > | TListSensors |
Public Types inherited from mvsim::Simulable | |
using | Ptr = std::shared_ptr< Simulable > |
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... | |
Controllers | |
typedef ControllerBaseTempl< DynamicsDifferential > | ControllerBase |
typedef std::shared_ptr< ControllerBase > | ControllerBasePtr |
const ControllerBasePtr & | getController () const |
ControllerBasePtr & | getController () |
virtual ControllerBaseInterface * | getControllerInterface () 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... | |
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 |
Implementation of differential-driven vehicles.
Definition at line 20 of file VehicleDifferential.h.
Virtual base for controllers of vehicles of type DynamicsDifferential
Definition at line 46 of file VehicleDifferential.h.
typedef std::shared_ptr<ControllerBase> mvsim::DynamicsDifferential::ControllerBasePtr |
Definition at line 47 of file VehicleDifferential.h.
anonymous enum |
Enumerator | |
---|---|
WHEEL_L | |
WHEEL_R |
Definition at line 24 of file VehicleDifferential.h.
DynamicsDifferential::DynamicsDifferential | ( | World * | parent | ) |
Definition at line 22 of file VehicleDifferential.cpp.
|
overrideprotectedvirtual |
The derived-class part of load_params_from_xml()
Implements mvsim::VehicleBase.
Definition at line 47 of file VehicleDifferential.cpp.
|
inline |
Definition at line 102 of file VehicleDifferential.h.
|
inline |
Definition at line 103 of file VehicleDifferential.h.
|
inlineoverridevirtual |
Implements mvsim::VehicleBase.
Definition at line 104 of file VehicleDifferential.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 150 of file VehicleDifferential.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VehicleBase.
Definition at line 130 of file VehicleDifferential.cpp.
|
private |
The installed controller.
Definition at line 123 of file VehicleDifferential.h.