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

#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 ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
const std::stringgetName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TTwist2D getTwist () const
 
const mrpt::math::TTwist2DgetVelocity () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
virtual void poses_mutex_lock ()=0
 
virtual void poses_mutex_unlock ()=0
 
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)
 

Protected Attributes

std::string m_name
 

Detailed Description

Definition at line 24 of file Simulable.h.

Member Typedef Documentation

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

Definition at line 27 of file Simulable.h.

Member Function Documentation

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 78 of file Simulable.cpp.

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

Definition at line 113 of file Simulable.h.

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

Definition at line 114 of file Simulable.h.

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

Alternative to getPose()

Definition at line 93 of file Simulable.cpp.

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

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

Definition at line 95 of file Simulable.h.

mrpt::math::TPose3D mvsim::Simulable::getPose ( ) const
inline

Last time-step pose (of the ref. point, in global coords) (ground-truth)

Definition at line 55 of file Simulable.h.

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

Definition at line 63 of file Simulable.h.

const mrpt::math::TTwist2D& mvsim::Simulable::getVelocity ( ) const
inline

Last time-step velocity (of the ref. point, in global coords) (ground-truth)

Definition at line 92 of file Simulable.h.

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

Last time-step velocity (of the ref. point, in local coords)

Definition at line 84 of file Simulable.cpp.

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 106 of file Simulable.h.

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

Whether is is in collision right now.

See also

Definition at line 101 of file Simulable.h.

virtual void mvsim::Simulable::poses_mutex_lock ( )
pure virtual
virtual void mvsim::Simulable::poses_mutex_unlock ( )
pure virtual
void Simulable::registerOnServer ( mvsim::Client c)
virtual

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

Definition at line 150 of file Simulable.cpp.

void mvsim::Simulable::resetCollisionFlag ( )
inline

Resets the condition reported by hadCollision() to false

Definition at line 109 of file Simulable.h.

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

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

Definition at line 98 of file Simulable.h.

void mvsim::Simulable::setPose ( const mrpt::math::TPose3D p) const
inline

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

Definition at line 73 of file Simulable.h.

void mvsim::Simulable::setTwist ( const mrpt::math::TTwist2D dq) const
inline

Definition at line 80 of file Simulable.h.

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 m_q, m_dq)

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

Definition at line 38 of file Simulable.cpp.

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::VehicleBase, mvsim::Block, mvsim::OccupancyGridMap, mvsim::LaserScanner, and mvsim::ElevationMap.

Definition at line 25 of file Simulable.cpp.

Member Data Documentation

std::string mvsim::Simulable::m_name
protected

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

Definition at line 118 of file Simulable.h.


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


mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:52