#include <Simulable.h>
Public Types | |
using | Ptr = std::shared_ptr< Simulable > |
Public Member Functions | |
virtual void | apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) |
b2Body * | b2d_body () |
const b2Body * | b2d_body () const |
virtual void | freeOpenGLResources () |
mrpt::poses::CPose2D | getCPose2D () const |
Alternative to getPose() More... | |
mrpt::poses::CPose3D | getCPose3D () const |
Alternative to getPose() More... | |
virtual std::optional< float > | getElevationAt ([[maybe_unused]] const mrpt::math::TPoint2D &worldXY) const |
mrpt::math::TVector3D | getLinearAcceleration () const |
const std::string & | getName () const |
mrpt::math::TPose3D | getPose () const |
mrpt::math::TPose3D | getPoseNoLock () const |
No thread-safe version. Used internally only. More... | |
virtual mrpt::math::TPose3D | getRelativePose () const |
World * | getSimulableWorldObject () |
const World * | getSimulableWorldObject () const |
mrpt::math::TTwist2D | getTwist () const |
mrpt::math::TTwist2D | getVelocityLocal () const |
bool | hadCollision () const |
bool | isInCollision () const |
virtual VisualObject * | meAsVisualObject () |
virtual void | registerOnServer (mvsim::Client &c) |
void | resetCollisionFlag () |
void | setName (const std::string &s) |
void | setPose (const mrpt::math::TPose3D &p, bool notifyChange=true) const |
virtual void | setRelativePose (const mrpt::math::TPose3D &p) |
void | setTwist (const mrpt::math::TTwist2D &dq) const |
virtual void | simul_post_timestep (const TSimulContext &context) |
virtual void | simul_pre_timestep (const TSimulContext &context) |
Simulable (World *parent) | |
Protected Attributes | |
std::string | name_ |
The basic virtual base class for all objects that can run in the simulated mvsim::World
Definition at line 39 of file Simulable.h.
using mvsim::Simulable::Ptr = std::shared_ptr<Simulable> |
Definition at line 42 of file Simulable.h.
|
inline |
Definition at line 44 of file Simulable.h.
|
virtual |
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 in mvsim::Block, and mvsim::VehicleBase.
Definition at line 135 of file Simulable.cpp.
|
inline |
Definition at line 126 of file Simulable.h.
|
inline |
Definition at line 125 of file Simulable.h.
|
inlinevirtual |
Reimplemented in mvsim::VehicleBase, mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, and mvsim::CameraSensor.
Definition at line 131 of file Simulable.h.
mrpt::poses::CPose2D Simulable::getCPose2D | ( | ) | const |
Alternative to getPose()
Definition at line 150 of file Simulable.cpp.
mrpt::poses::CPose3D Simulable::getCPose3D | ( | ) | const |
Alternative to getPose()
Definition at line 157 of file Simulable.cpp.
|
inlinevirtual |
If the given world-frame 2D coordinates are within the limits of this entity, this method returns the ground height or elevation or "z" coordinate of the object for the queried (x,y). If the coordinates do not affect this object, it will return nullopt.
Definition at line 137 of file Simulable.h.
mrpt::math::TVector3D Simulable::getLinearAcceleration | ( | ) | const |
Last time-step acceleration of the ref. point (global coords). Note this is the "coordinate acceleration" vector, not the proper acceleration. It is simply estimated as a finite difference of dq_.
Definition at line 504 of file Simulable.cpp.
|
inline |
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 107 of file Simulable.h.
mrpt::math::TPose3D Simulable::getPose | ( | ) | const |
Last time-step pose (of the ref. point, in global coords) (ground-truth)
Definition at line 490 of file Simulable.cpp.
mrpt::math::TPose3D Simulable::getPoseNoLock | ( | ) | const |
No thread-safe version. Used internally only.
Definition at line 496 of file Simulable.cpp.
|
inlinevirtual |
Like getPose(), but gets the relative pose with respect to the parent object, or just exactly like getPose() (global pose) if this is a top-level entity.
Reimplemented in mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::CameraSensor, mvsim::GNSS, and mvsim::IMU.
Definition at line 77 of file Simulable.h.
|
inline |
Definition at line 128 of file Simulable.h.
|
inline |
Definition at line 129 of file Simulable.h.
mrpt::math::TTwist2D Simulable::getTwist | ( | ) | const |
Definition at line 498 of file Simulable.cpp.
mrpt::math::TTwist2D Simulable::getVelocityLocal | ( | ) | const |
Last time-step velocity (of the ref. point, in local coords)
Definition at line 141 of file Simulable.cpp.
bool Simulable::hadCollision | ( | ) | const |
Whether a collision occurred since the last time this flag was manually reset.
Definition at line 169 of file Simulable.cpp.
bool Simulable::isInCollision | ( | ) | const |
|
inlinevirtual |
Reimplemented in mvsim::VehicleBase, and mvsim::Block.
Definition at line 64 of file Simulable.h.
|
virtual |
Reimplemented in mvsim::DummyInvisibleBlock, mvsim::VehicleBase, mvsim::SensorBase, mvsim::LaserScanner, mvsim::GNSS, and mvsim::IMU.
Definition at line 458 of file Simulable.cpp.
void Simulable::resetCollisionFlag | ( | ) |
Resets the condition reported by hadCollision() to false
Definition at line 175 of file Simulable.cpp.
|
inline |
Changes object name (e.g. "r1", "veh1")
Definition at line 110 of file Simulable.h.
void Simulable::setPose | ( | const mrpt::math::TPose3D & | p, |
bool | notifyChange = true |
||
) | const |
Manually override vehicle pose (Use with caution!) (purposely set a "const")
Definition at line 474 of file Simulable.cpp.
|
inlinevirtual |
Changes the relative pose of this object with respect to its parent, or the global frame if its a top-level entity.
Reimplemented in mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::CameraSensor, mvsim::GNSS, and mvsim::IMU.
Definition at line 96 of file Simulable.h.
void Simulable::setTwist | ( | const mrpt::math::TTwist2D & | dq | ) | const |
Definition at line 510 of file Simulable.cpp.
|
virtual |
Override to do any required process right after the integration of dynamic equations for each timestep. IMPORTANT: Reimplementations MUST also call this base method, since it is in charge of important tasks (e.g. update q_, dq_)
Reimplemented in mvsim::DummyInvisibleBlock, mvsim::Block, mvsim::VehicleBase, mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::ElevationMap, mvsim::GNSS, mvsim::CameraSensor, mvsim::IMU, mvsim::VerticalPlane, and mvsim::HorizontalPlane.
Definition at line 64 of file Simulable.cpp.
|
virtual |
Process right before the integration of dynamic equations for each timestep: set action forces from motors, update friction models, etc.
Reimplemented in mvsim::DummyInvisibleBlock, mvsim::Block, mvsim::VehicleBase, mvsim::DepthCameraSensor, mvsim::OccupancyGridMap, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::PointCloud, mvsim::ElevationMap, mvsim::GNSS, mvsim::CameraSensor, mvsim::IMU, mvsim::VerticalPlane, and mvsim::HorizontalPlane.
Definition at line 35 of file Simulable.cpp.
|
protected |
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 145 of file Simulable.h.