#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 () |
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... | |
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) 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_ |
Definition at line 34 of file Simulable.h.
using mvsim::Simulable::Ptr = std::shared_ptr<Simulable> |
Definition at line 37 of file Simulable.h.
|
inline |
Definition at line 39 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 110 of file Simulable.cpp.
|
inline |
Definition at line 110 of file Simulable.h.
|
inline |
Definition at line 111 of file Simulable.h.
|
inlinevirtual |
Reimplemented in mvsim::VehicleBase, mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, and mvsim::CameraSensor.
Definition at line 116 of file Simulable.h.
mrpt::poses::CPose2D Simulable::getCPose2D | ( | ) | const |
Alternative to getPose()
Definition at line 125 of file Simulable.cpp.
mrpt::poses::CPose3D Simulable::getCPose3D | ( | ) | const |
Alternative to getPose()
Definition at line 132 of file Simulable.cpp.
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.
|
inline |
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 92 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 438 of file Simulable.cpp.
mrpt::math::TPose3D Simulable::getPoseNoLock | ( | ) | const |
No thread-safe version. Used internally only.
Definition at line 446 of file Simulable.cpp.
|
inline |
Definition at line 113 of file Simulable.h.
|
inline |
Definition at line 114 of file Simulable.h.
mrpt::math::TTwist2D Simulable::getTwist | ( | ) | const |
Definition at line 448 of file Simulable.cpp.
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.
|
inline |
Whether a collision occurred since the last time this flag was manually reset.
Definition at line 103 of file Simulable.h.
|
inline |
|
inlinevirtual |
Reimplemented in mvsim::VehicleBase, and mvsim::Block.
Definition at line 59 of file Simulable.h.
|
virtual |
Reimplemented in mvsim::DummyInvisibleBlock, mvsim::VehicleBase, mvsim::LaserScanner, mvsim::SensorBase, and mvsim::IMU.
Definition at line 406 of file Simulable.cpp.
|
inline |
Resets the condition reported by hadCollision() to false
Definition at line 106 of file Simulable.h.
|
inline |
Changes object name (e.g. "r1", "veh1")
Definition at line 95 of file Simulable.h.
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.
void Simulable::setTwist | ( | const mrpt::math::TTwist2D & | dq | ) | const |
Definition at line 464 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::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.
|
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.
|
protected |
User-supplied name of the vehicle (e.g. "r1", "veh1")
Definition at line 120 of file Simulable.h.