#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)) | 
| const b2Body * | b2d_body () const | 
| b2Body * | b2d_body () | 
| mrpt::poses::CPose2D | getCPose2D () const | 
| Alternative to getPose()  More... | |
| const std::string & | getName () const | 
| mrpt::math::TPose3D | getPose () const | 
| mrpt::math::TTwist2D | getTwist () const | 
| const mrpt::math::TTwist2D & | getVelocity () 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 | 
Definition at line 24 of file Simulable.h.
| using mvsim::Simulable::Ptr = std::shared_ptr<Simulable> | 
Definition at line 27 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::VehicleBase, and mvsim::Block.
Definition at line 78 of file Simulable.cpp.
Definition at line 113 of file Simulable.h.
| 
 | 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.
| 
 | inline | 
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 95 of file Simulable.h.
| 
 | inline | 
Last time-step pose (of the ref. point, in global coords) (ground-truth)
Definition at line 55 of file Simulable.h.
| 
 | inline | 
Definition at line 63 of file Simulable.h.
| 
 | 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.
| 
 | inline | 
Whether a collision occurred since the last time this flag was manually reset.
Definition at line 106 of file Simulable.h.
| 
 | inline | 
| 
 | pure virtual | 
Implemented in mvsim::Block, mvsim::VehicleBase, mvsim::OccupancyGridMap, mvsim::LaserScanner, mvsim::ElevationMap, and mvsim::GroundGrid.
| 
 | pure virtual | 
Implemented in mvsim::Block, mvsim::VehicleBase, mvsim::OccupancyGridMap, mvsim::LaserScanner, mvsim::ElevationMap, and mvsim::GroundGrid.
| 
 | virtual | 
Reimplemented in mvsim::VehicleBase, and mvsim::SensorBase.
Definition at line 150 of file Simulable.cpp.
| 
 | inline | 
Resets the condition reported by hadCollision() to false
Definition at line 109 of file Simulable.h.
| 
 | inline | 
Changes object name (e.g. "r1", "veh1")
Definition at line 98 of file Simulable.h.
| 
 | inline | 
Manually override vehicle pose (Use with caution!) (purposely set a "const")
Definition at line 73 of file Simulable.h.
| 
 | inline | 
Definition at line 80 of file Simulable.h.
| 
 | 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.
| 
 | 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.
| 
 | protected | 
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 118 of file Simulable.h.