RobWorkProject  24.12.4-
Public Types | Public Member Functions | List of all members
SimulatedScanner25D Class Reference

a simulated range scanner for 2.5D images, that is basically pointclouds without color information. More...

#include <SimulatedScanner25D.hpp>

Inherits SimulatedSensor.

Public Types

typedef rw::core::Ptr< SimulatedScanner25DPtr
 smart pointer type of this class
 
- Public Types inherited from SimulatedSensor
typedef rw::core::Ptr< SimulatedSensorPtr
 smart pointer type of this class
 
- Public Types inherited from Stateless
typedef rw::core::Ptr< StatelessPtr
 Smart pointer type for Stateless.
 

Public Member Functions

 SimulatedScanner25D (const std::string &name, rw::core::Ptr< rw::kinematics::Frame > frame, rw::core::Ptr< rwlibs::simulation::FrameGrabber25D > framegrabber)
 constructor More...
 
 SimulatedScanner25D (const std::string &name, const std::string &desc, rw::core::Ptr< rw::kinematics::Frame > frame, rw::core::Ptr< rwlibs::simulation::FrameGrabber25D > framegrabber)
 constructor More...
 
virtual ~SimulatedScanner25D ()
 destructor
 
void setFrameRate (double rate)
 set the framerate in frames per sec. More...
 
void open ()
 Opens connection to the scanner. More...
 
bool isOpen ()
 Returns whether the scanner has been opened. More...
 
void close ()
 Closes the connection to the scanner. More...
 
void acquire ()
 Acquires data. More...
 
bool isScanReady ()
 tests whether an image has been acquired More...
 
std::pair< double, double > getRange ()
 Returns the min and max range of this Scanner. More...
 
double getFrameRate ()
 returns the framerate that this camera is setup with More...
 
const rw::geometry::PointCloudgetScan ()
 returns a char pointer to the image data More...
 
void update (const Simulator::UpdateInfo &info, rw::kinematics::State &state)
 steps the the SimulatedSensor with time dt and saves any state changes in state. More...
 
void reset (const rw::kinematics::State &state)
 Resets the state of the SimulatedSensor to that of state. More...
 
rw::core::Ptr< rw::sensor::SensorgetSensorHandle (rw::core::Ptr< rwlibs::simulation::Simulator > instance)
 get a handle to controlling an instance of the simulated sensor in a specific simulator More...
 
rw::core::Ptr< rw::sensor::Scanner25DgetScanner25DSensor (rw::core::Ptr< rwlibs::simulation::Simulator > instance)
 get instance of scanner
 
- Public Member Functions inherited from SimulatedSensor
virtual ~SimulatedSensor ()
 destructor
 
const std::string & getName () const
 get name of this simulated sensor
 
rw::kinematics::FramegetFrame () const
 get frame that this sensor is attached to. More...
 
rw::sensor::SensorModel::Ptr getSensorModel ()
 get the sensor model of this simulated sensor.
 
rw::sensor::Sensor::Ptr getSensorHandle (rwlibs::simulation::Simulator::Ptr sim)
 get a handle to controlling an instance of the simulated sensor in a specific simulator More...
 
- Public Member Functions inherited from Stateless
virtual ~Stateless ()
 destructor
 
virtual void registerIn (State &state)
 initialize this stateless data to a specific state More...
 
virtual void registerIn (StateStructure::Ptr state)
 register this stateless object in a statestructure.
 
virtual void unregister ()
 unregisters all state data of this stateless object
 
StateStructure::Ptr getStateStructure ()
 Get the state structure. More...
 
const StateStructure::Ptr getStateStructure () const
 Get the state structure. More...
 
bool isRegistered ()
 Check if object has registered its state. More...
 

Additional Inherited Members

- Protected Member Functions inherited from SimulatedSensor
 SimulatedSensor (rw::sensor::SensorModel::Ptr model)
 constructor
 
- Protected Member Functions inherited from Stateless
 Stateless ()
 constructor
 
template<class T >
void add (StatelessData< T > &data)
 implementations of sensor should add all their stateless data on initialization
 
void add (StateData *data)
 Add data. More...
 
void add (rw::core::Ptr< StateData > data)
 implementations of sensor should add all their state data on initialization
 
- Protected Attributes inherited from Stateless
bool _registered
 True if object has registered its state.
 
std::vector< rw::core::Ptr< StateData > > _datas
 Data.
 
StateStructure::Ptr _stateStruct
 The state structure.
 

Detailed Description

a simulated range scanner for 2.5D images, that is basically pointclouds without color information.

Constructor & Destructor Documentation

◆ SimulatedScanner25D() [1/2]

SimulatedScanner25D ( const std::string &  name,
rw::core::Ptr< rw::kinematics::Frame frame,
rw::core::Ptr< rwlibs::simulation::FrameGrabber25D framegrabber 
)

constructor

Parameters
name[in] name of this simulated scanner
frame[in] the frame the scanner is attached to.
framegrabber[in] the framegrabber used for grabbing 2.5D images

◆ SimulatedScanner25D() [2/2]

SimulatedScanner25D ( const std::string &  name,
const std::string &  desc,
rw::core::Ptr< rw::kinematics::Frame frame,
rw::core::Ptr< rwlibs::simulation::FrameGrabber25D framegrabber 
)

constructor

Parameters
name[in] name of this simulated scanner
desc[in] description of this scanner
frame[in] the frame the scanner is attached to.
framegrabber[in] the framegrabber used for grabbing 2.5D images

Member Function Documentation

◆ acquire()

void acquire ( )

Acquires data.

◆ close()

void close ( )

Closes the connection to the scanner.

◆ getFrameRate()

double getFrameRate ( )

returns the framerate that this camera is setup with

Returns
the framerate in frames per second

◆ getRange()

std::pair<double, double> getRange ( )

Returns the min and max range of this Scanner.

Returns
min and max range

◆ getScan()

const rw::geometry::PointCloud& getScan ( )

returns a char pointer to the image data

Returns
char pointer to the image data

◆ getSensorHandle()

get a handle to controlling an instance of the simulated sensor in a specific simulator

Parameters
instance[in] the simulator in which the handle is active

◆ isOpen()

bool isOpen ( )

Returns whether the scanner has been opened.

Returns
true if scanner is opened

◆ isScanReady()

bool isScanReady ( )

tests whether an image has been acquired

Returns
true if an image has been acquired, false otherwise.

◆ open()

void open ( )

Opens connection to the scanner.

◆ reset()

void reset ( const rw::kinematics::State state)
virtual

Resets the state of the SimulatedSensor to that of state.

Parameters
state[in] the state that the sensor is reset too.

Implements SimulatedSensor.

◆ setFrameRate()

void setFrameRate ( double  rate)

set the framerate in frames per sec.

Parameters
rate[in] frames per sec

◆ update()

void update ( const Simulator::UpdateInfo info,
rw::kinematics::State state 
)
virtual

steps the the SimulatedSensor with time dt and saves any state changes in state.

Parameters
info[in] update information related to the time step.
state[out] changes of the SimulatedSensor is saved in state.

Implements SimulatedSensor.


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