Public Types | Public Member Functions | Protected Attributes | List of all members
mvsim::Simulable Class Reference

#include <Simulable.h>

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

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))
 
b2Bodyb2d_body ()
 
const b2Bodyb2d_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
 
WorldgetSimulableWorldObject ()
 
const WorldgetSimulableWorldObject () const
 
mrpt::math::TTwist2D getTwist () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
virtual VisualObjectmeAsVisualObject ()
 
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_
 

Detailed Description

The basic virtual base class for all objects that can run in the simulated mvsim::World

Definition at line 39 of file Simulable.h.

Member Typedef Documentation

◆ Ptr

using mvsim::Simulable::Ptr = std::shared_ptr<Simulable>

Definition at line 42 of file Simulable.h.

Constructor & Destructor Documentation

◆ Simulable()

mvsim::Simulable::Simulable ( World parent)
inline

Definition at line 44 of file Simulable.h.

Member Function Documentation

◆ apply_force()

void Simulable::apply_force ( const mrpt::math::TVector2D &  force,
const mrpt::math::TPoint2D &  applyPoint = mrpt::math::TPoint2D(0, 0) 
)
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.

◆ b2d_body() [1/2]

b2Body* mvsim::Simulable::b2d_body ( )
inline

Definition at line 126 of file Simulable.h.

◆ b2d_body() [2/2]

const b2Body* mvsim::Simulable::b2d_body ( ) const
inline

Definition at line 125 of file Simulable.h.

◆ freeOpenGLResources()

virtual void mvsim::Simulable::freeOpenGLResources ( )
inlinevirtual

◆ getCPose2D()

mrpt::poses::CPose2D Simulable::getCPose2D ( ) const

Alternative to getPose()

Definition at line 150 of file Simulable.cpp.

◆ getCPose3D()

mrpt::poses::CPose3D Simulable::getCPose3D ( ) const

Alternative to getPose()

Definition at line 157 of file Simulable.cpp.

◆ getElevationAt()

virtual std::optional<float> mvsim::Simulable::getElevationAt ( [[maybe_unused] ] const mrpt::math::TPoint2D &  worldXY) const
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.

◆ getLinearAcceleration()

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.

◆ getName()

const std::string& mvsim::Simulable::getName ( ) const
inline

User-supplied name of the vehicle (e.g. "r1", "veh1")

Definition at line 107 of file Simulable.h.

◆ getPose()

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.

◆ getPoseNoLock()

mrpt::math::TPose3D Simulable::getPoseNoLock ( ) const

No thread-safe version. Used internally only.

Definition at line 496 of file Simulable.cpp.

◆ getRelativePose()

virtual mrpt::math::TPose3D mvsim::Simulable::getRelativePose ( ) const
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.

◆ getSimulableWorldObject() [1/2]

World* mvsim::Simulable::getSimulableWorldObject ( )
inline

Definition at line 128 of file Simulable.h.

◆ getSimulableWorldObject() [2/2]

const World* mvsim::Simulable::getSimulableWorldObject ( ) const
inline

Definition at line 129 of file Simulable.h.

◆ getTwist()

mrpt::math::TTwist2D Simulable::getTwist ( ) const

Definition at line 498 of file Simulable.cpp.

◆ getVelocityLocal()

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.

◆ hadCollision()

bool Simulable::hadCollision ( ) const

Whether a collision occurred since the last time this flag was manually reset.

See also
isInCollision(), resetCollisionFlag()

Definition at line 169 of file Simulable.cpp.

◆ isInCollision()

bool Simulable::isInCollision ( ) const

Whether is is in collision right now.

See also

Definition at line 163 of file Simulable.cpp.

◆ meAsVisualObject()

virtual VisualObject* mvsim::Simulable::meAsVisualObject ( )
inlinevirtual

Reimplemented in mvsim::VehicleBase, and mvsim::Block.

Definition at line 64 of file Simulable.h.

◆ registerOnServer()

void Simulable::registerOnServer ( mvsim::Client c)
virtual

◆ resetCollisionFlag()

void Simulable::resetCollisionFlag ( )

Resets the condition reported by hadCollision() to false

Definition at line 175 of file Simulable.cpp.

◆ setName()

void mvsim::Simulable::setName ( const std::string &  s)
inline

Changes object name (e.g. "r1", "veh1")

Definition at line 110 of file Simulable.h.

◆ setPose()

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.

◆ setRelativePose()

virtual void mvsim::Simulable::setRelativePose ( const mrpt::math::TPose3D &  p)
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.

◆ setTwist()

void Simulable::setTwist ( const mrpt::math::TTwist2D &  dq) const

Definition at line 510 of file Simulable.cpp.

◆ simul_post_timestep()

void Simulable::simul_post_timestep ( const TSimulContext context)
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.

◆ simul_pre_timestep()

void Simulable::simul_pre_timestep ( const TSimulContext context)
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.

Member Data Documentation

◆ name_

std::string mvsim::Simulable::name_
protected

User-supplied name of the vehicle (e.g. "r1", "veh1")

Definition at line 145 of file Simulable.h.


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


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:10