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))
 
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
virtual void freeOpenGLResources ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
mrpt::poses::CPose3D getCPose3D () const
 Alternative to getPose() More...
 
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...
 
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) const
 
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

Definition at line 34 of file Simulable.h.

Member Typedef Documentation

◆ Ptr

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

Definition at line 37 of file Simulable.h.

Constructor & Destructor Documentation

◆ Simulable()

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

Definition at line 39 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::VehicleBase, and mvsim::Block.

Definition at line 110 of file Simulable.cpp.

◆ b2d_body() [1/2]

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

Definition at line 110 of file Simulable.h.

◆ b2d_body() [2/2]

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

Definition at line 111 of file Simulable.h.

◆ freeOpenGLResources()

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

◆ getCPose2D()

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

Alternative to getPose()

Definition at line 125 of file Simulable.cpp.

◆ getCPose3D()

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

Alternative to getPose()

Definition at line 132 of file Simulable.cpp.

◆ 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 456 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 92 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 438 of file Simulable.cpp.

◆ getPoseNoLock()

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

No thread-safe version. Used internally only.

Definition at line 446 of file Simulable.cpp.

◆ getSimulableWorldObject() [1/2]

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

Definition at line 113 of file Simulable.h.

◆ getSimulableWorldObject() [2/2]

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

Definition at line 114 of file Simulable.h.

◆ getTwist()

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

Definition at line 448 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 116 of file Simulable.cpp.

◆ hadCollision()

bool mvsim::Simulable::hadCollision ( ) const
inline

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

See also
isInCollision(), resetCollisionFlag()

Definition at line 103 of file Simulable.h.

◆ isInCollision()

bool mvsim::Simulable::isInCollision ( ) const
inline

Whether is is in collision right now.

See also

Definition at line 98 of file Simulable.h.

◆ meAsVisualObject()

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

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

Definition at line 59 of file Simulable.h.

◆ registerOnServer()

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

◆ resetCollisionFlag()

void mvsim::Simulable::resetCollisionFlag ( )
inline

Resets the condition reported by hadCollision() to false

Definition at line 106 of file Simulable.h.

◆ setName()

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

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

Definition at line 95 of file Simulable.h.

◆ setPose()

void Simulable::setPose ( const mrpt::math::TPose3D &  p) const

Manually override vehicle pose (Use with caution!) (purposely set a "const")

Definition at line 423 of file Simulable.cpp.

◆ setTwist()

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

Definition at line 464 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::VehicleBase, mvsim::Block, mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::IMU, mvsim::CameraSensor, mvsim::VerticalPlane, mvsim::ElevationMap, and mvsim::HorizontalPlane.

Definition at line 59 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::VehicleBase, mvsim::Block, mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::OccupancyGridMap, mvsim::IMU, mvsim::PointCloud, mvsim::CameraSensor, mvsim::VerticalPlane, mvsim::ElevationMap, and mvsim::HorizontalPlane.

Definition at line 30 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 120 of file Simulable.h.


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


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:23