Laser rotates around the zaxis and it's 0 angle is pointed toward the xaxis. More...
#include <roslaser2d.h>
Classes | |
class | BaseLaser2DXMLReader |
Public Member Functions | |
virtual int | Configure (ConfigureCommand command, bool blocking) |
virtual SensorDataPtr | CreateSensorData (SensorType type) |
virtual bool | GetSensorData (SensorDataPtr psensordata) |
virtual SensorGeometryPtr | GetSensorGeometry (SensorType type) |
virtual Transform | GetTransform () |
ROSLaser2D (EnvironmentBasePtr penv) | |
virtual bool | SendCommand (std::ostream &os, std::istream &is) |
virtual void | SetTransform (const Transform &trans) |
virtual bool | SimulationStep (dReal fTimeElapsed) |
virtual void | startsubscriptions () |
virtual bool | Supports (SensorType type) |
virtual | ~ROSLaser2D () |
Static Public Member Functions | |
static BaseXMLReaderPtr | CreateXMLReader (InterfaceBasePtr ptr, const std::list< std::pair< std::string, std::string > > &atts) |
Protected Member Functions | |
virtual void | _RenderGeometry () |
virtual void | _Reset () |
void | _SensorThread () |
virtual Transform | GetLaserPlaneTransform () |
virtual void | newscan_cb (const sensor_msgs::LaserScanConstPtr &msg) |
Protected Attributes | |
bool | _bDestroyThread |
bool | _bPower |
bool | _bRenderData |
bool | _bRenderGeometry |
bool | _bUpdatePlot |
GraphHandlePtr | _graphgeometry |
list< GraphHandlePtr > | _listGraphicsHandles |
boost::mutex | _mutexdata |
boost::shared_ptr < ros::NodeHandle > | _node |
boost::shared_ptr < LaserSensorData > | _pdata |
boost::shared_ptr< LaserGeomData > | _pgeom |
ros::Subscriber | _submstate |
boost::thread | _threadsensor |
Transform | _trans |
RaveVector< float > | _vColor |
string | scantopic |
Friends | |
class | BaseLaser2DXMLReader |
Laser rotates around the zaxis and it's 0 angle is pointed toward the xaxis.
Definition at line 23 of file roslaser2d.h.
ROSLaser2D::ROSLaser2D | ( | EnvironmentBasePtr | penv | ) | [inline] |
Definition at line 94 of file roslaser2d.h.
virtual ROSLaser2D::~ROSLaser2D | ( | ) | [inline, virtual] |
Definition at line 112 of file roslaser2d.h.
virtual void ROSLaser2D::_RenderGeometry | ( | ) | [inline, protected, virtual] |
Definition at line 268 of file roslaser2d.h.
virtual void ROSLaser2D::_Reset | ( | ) | [inline, protected, virtual] |
Definition at line 250 of file roslaser2d.h.
void ROSLaser2D::_SensorThread | ( | ) | [inline, protected] |
Definition at line 373 of file roslaser2d.h.
virtual int ROSLaser2D::Configure | ( | ConfigureCommand | command, |
bool | blocking | ||
) | [inline, virtual] |
Definition at line 117 of file roslaser2d.h.
virtual SensorDataPtr ROSLaser2D::CreateSensorData | ( | SensorType | type | ) | [inline, virtual] |
Definition at line 193 of file roslaser2d.h.
static BaseXMLReaderPtr ROSLaser2D::CreateXMLReader | ( | InterfaceBasePtr | ptr, |
const std::list< std::pair< std::string, std::string > > & | atts | ||
) | [inline, static] |
Definition at line 89 of file roslaser2d.h.
virtual Transform ROSLaser2D::GetLaserPlaneTransform | ( | ) | [inline, protected, virtual] |
Definition at line 305 of file roslaser2d.h.
virtual bool ROSLaser2D::GetSensorData | ( | SensorDataPtr | psensordata | ) | [inline, virtual] |
Definition at line 201 of file roslaser2d.h.
virtual SensorGeometryPtr ROSLaser2D::GetSensorGeometry | ( | SensorType | type | ) | [inline, virtual] |
Definition at line 183 of file roslaser2d.h.
virtual Transform ROSLaser2D::GetTransform | ( | ) | [inline, virtual] |
Definition at line 246 of file roslaser2d.h.
virtual void ROSLaser2D::newscan_cb | ( | const sensor_msgs::LaserScanConstPtr & | msg | ) | [inline, protected, virtual] |
Definition at line 306 of file roslaser2d.h.
virtual bool ROSLaser2D::SendCommand | ( | std::ostream & | os, |
std::istream & | is | ||
) | [inline, virtual] |
Definition at line 213 of file roslaser2d.h.
virtual void ROSLaser2D::SetTransform | ( | const Transform & | trans | ) | [inline, virtual] |
Definition at line 240 of file roslaser2d.h.
virtual bool ROSLaser2D::SimulationStep | ( | dReal | fTimeElapsed | ) | [inline, virtual] |
Definition at line 174 of file roslaser2d.h.
virtual void ROSLaser2D::startsubscriptions | ( | ) | [inline, virtual] |
Definition at line 158 of file roslaser2d.h.
virtual bool ROSLaser2D::Supports | ( | SensorType | type | ) | [inline, virtual] |
Definition at line 211 of file roslaser2d.h.
friend class BaseLaser2DXMLReader [friend] |
Definition at line 402 of file roslaser2d.h.
bool ROSLaser2D::_bDestroyThread [protected] |
Definition at line 397 of file roslaser2d.h.
bool ROSLaser2D::_bPower [protected] |
Definition at line 399 of file roslaser2d.h.
bool ROSLaser2D::_bRenderData [protected] |
Definition at line 399 of file roslaser2d.h.
bool ROSLaser2D::_bRenderGeometry [protected] |
Definition at line 399 of file roslaser2d.h.
bool ROSLaser2D::_bUpdatePlot [protected] |
Definition at line 400 of file roslaser2d.h.
GraphHandlePtr ROSLaser2D::_graphgeometry [protected] |
Definition at line 393 of file roslaser2d.h.
list<GraphHandlePtr> ROSLaser2D::_listGraphicsHandles [protected] |
Definition at line 392 of file roslaser2d.h.
boost::mutex ROSLaser2D::_mutexdata [protected] |
Definition at line 395 of file roslaser2d.h.
boost::shared_ptr<ros::NodeHandle> ROSLaser2D::_node [protected] |
Definition at line 381 of file roslaser2d.h.
boost::shared_ptr<LaserSensorData> ROSLaser2D::_pdata [protected] |
Definition at line 385 of file roslaser2d.h.
boost::shared_ptr<LaserGeomData> ROSLaser2D::_pgeom [protected] |
Definition at line 384 of file roslaser2d.h.
ros::Subscriber ROSLaser2D::_submstate [protected] |
Definition at line 382 of file roslaser2d.h.
boost::thread ROSLaser2D::_threadsensor [protected] |
Definition at line 396 of file roslaser2d.h.
Transform ROSLaser2D::_trans [protected] |
Definition at line 391 of file roslaser2d.h.
RaveVector<float> ROSLaser2D::_vColor [protected] |
Definition at line 389 of file roslaser2d.h.
string ROSLaser2D::scantopic [protected] |
Definition at line 388 of file roslaser2d.h.