Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
or_octomap::OctomapInterface Class Reference

#include <OctomapInterface.h>

Inheritance diagram for or_octomap::OctomapInterface:
Inheritance graph
[legend]

Public Member Functions

virtual OpenRAVE::KinBody::ManageDataPtr AddKinBody (OpenRAVE::KinBodyPtr pbody, OpenRAVE::XMLReadableConstPtr pdata)
 
virtual void AddRegisteredBodies (const std::vector< OpenRAVE::KinBodyPtr > &vbodies)
 
bool Disable (std::ostream &os, std::istream &i)
 
bool Enable (std::ostream &os, std::istream &i)
 
virtual bool EnableBody (OpenRAVE::KinBodyPtr pbody, bool bEnable)
 
boost::mutex & GetMutex ()
 
octomap::OcTree * GetTree ()
 
virtual bool IsBodyPresent (OpenRAVE::KinBodyPtr pbody)
 
bool IsEnabled ()
 
bool MaskObject (std::ostream &os, std::istream &i)
 
 OctomapInterface (ros::NodeHandle &nodeHandle, OpenRAVE::EnvironmentBasePtr env)
 
virtual bool RemoveKinBody (OpenRAVE::KinBodyPtr pbody)
 
virtual void Reset ()
 
bool ResetFrame (std::ostream &os, std::istream &i)
 
bool ResetResolution (std::ostream &os, std::istream &i)
 
bool ResetTopic (std::ostream &os, std::istream &i)
 
bool ResetTree (std::ostream &os, std::istream &i)
 
bool SaveTree (std::ostream &os, std::istream &i)
 
virtual bool SendCommand (std::ostream &os, std::istream &is)
 
void SetEnabled (bool enabled)
 
void Spin ()
 
virtual bool SwitchBody (OpenRAVE::KinBodyPtr pbody1, OpenRAVE::KinBodyPtr pbody2)
 
void TestCollision ()
 
bool TogglePause (std::ostream &os, std::istream &i)
 
virtual ~OctomapInterface ()
 

Protected Member Functions

void CreateFakeBody ()
 
void DestroyFakeBody ()
 
void InsertCloudWrapper (const sensor_msgs::PointCloud2::ConstPtr &cloud)
 
void InsertScans ()
 
void updateParam ()
 

Protected Attributes

std::vector< sensor_msgs::PointCloud2ConstPtr > m_cloudQueue
 
boost::mutex m_cloudQueueMutex
 
OctomapCollisionCheckerm_collisionChecker
 
bool m_isEnabled
 
bool m_isPaused
 
ros::CallbackQueue m_queue
 
bool m_shouldExit
 

Detailed Description

Definition at line 23 of file OctomapInterface.h.

Constructor & Destructor Documentation

or_octomap::OctomapInterface::OctomapInterface ( ros::NodeHandle &  nodeHandle,
OpenRAVE::EnvironmentBasePtr  env 
)

Definition at line 27 of file OctomapInterface.cpp.

or_octomap::OctomapInterface::~OctomapInterface ( )
virtual

Definition at line 187 of file OctomapInterface.cpp.

Member Function Documentation

virtual OpenRAVE::KinBody::ManageDataPtr or_octomap::OctomapInterface::AddKinBody ( OpenRAVE::KinBodyPtr  pbody,
OpenRAVE::XMLReadableConstPtr  pdata 
)
inlinevirtual

Definition at line 39 of file OctomapInterface.h.

virtual void or_octomap::OctomapInterface::AddRegisteredBodies ( const std::vector< OpenRAVE::KinBodyPtr > &  vbodies)
inlinevirtual

Definition at line 38 of file OctomapInterface.h.

void or_octomap::OctomapInterface::CreateFakeBody ( )
protected

Definition at line 236 of file OctomapInterface.cpp.

void or_octomap::OctomapInterface::DestroyFakeBody ( )
protected

Definition at line 226 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::Disable ( std::ostream &  os,
std::istream &  i 
)
inline

Definition at line 51 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::Enable ( std::ostream &  os,
std::istream &  i 
)
inline

Definition at line 50 of file OctomapInterface.h.

virtual bool or_octomap::OctomapInterface::EnableBody ( OpenRAVE::KinBodyPtr  pbody,
bool  bEnable 
)
inlinevirtual

Definition at line 46 of file OctomapInterface.h.

boost::mutex& or_octomap::OctomapInterface::GetMutex ( )
inline

Definition at line 58 of file OctomapInterface.h.

octomap::OcTree* or_octomap::OctomapInterface::GetTree ( )
inline

Definition at line 35 of file OctomapInterface.h.

void or_octomap::OctomapInterface::InsertCloudWrapper ( const sensor_msgs::PointCloud2::ConstPtr &  cloud)
protected

Definition at line 122 of file OctomapInterface.cpp.

void or_octomap::OctomapInterface::InsertScans ( )
protected

Definition at line 132 of file OctomapInterface.cpp.

virtual bool or_octomap::OctomapInterface::IsBodyPresent ( OpenRAVE::KinBodyPtr  pbody)
inlinevirtual

Definition at line 45 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::IsEnabled ( )
inline

Definition at line 33 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::MaskObject ( std::ostream &  os,
std::istream &  i 
)

Definition at line 328 of file OctomapInterface.cpp.

virtual bool or_octomap::OctomapInterface::RemoveKinBody ( OpenRAVE::KinBodyPtr  pbody)
inlinevirtual

Definition at line 44 of file OctomapInterface.h.

void or_octomap::OctomapInterface::Reset ( )
virtual

Definition at line 249 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::ResetFrame ( std::ostream &  os,
std::istream &  i 
)

Definition at line 297 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::ResetResolution ( std::ostream &  os,
std::istream &  i 
)

Definition at line 274 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::ResetTopic ( std::ostream &  os,
std::istream &  i 
)

Definition at line 406 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::ResetTree ( std::ostream &  os,
std::istream &  i 
)

Definition at line 256 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::SaveTree ( std::ostream &  os,
std::istream &  i 
)

Definition at line 344 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::SendCommand ( std::ostream &  os,
std::istream &  is 
)
virtual

Definition at line 244 of file OctomapInterface.cpp.

void or_octomap::OctomapInterface::SetEnabled ( bool  enabled)

Definition at line 193 of file OctomapInterface.cpp.

void or_octomap::OctomapInterface::Spin ( )

Definition at line 176 of file OctomapInterface.cpp.

virtual bool or_octomap::OctomapInterface::SwitchBody ( OpenRAVE::KinBodyPtr  pbody1,
OpenRAVE::KinBodyPtr  pbody2 
)
inlinevirtual

Definition at line 47 of file OctomapInterface.h.

void or_octomap::OctomapInterface::TestCollision ( )

Definition at line 143 of file OctomapInterface.cpp.

bool or_octomap::OctomapInterface::TogglePause ( std::ostream &  os,
std::istream &  i 
)
inline

Definition at line 49 of file OctomapInterface.h.

void or_octomap::OctomapInterface::updateParam ( )
protected

Definition at line 66 of file OctomapInterface.cpp.

Member Data Documentation

std::vector<sensor_msgs::PointCloud2ConstPtr> or_octomap::OctomapInterface::m_cloudQueue
protected

Definition at line 73 of file OctomapInterface.h.

boost::mutex or_octomap::OctomapInterface::m_cloudQueueMutex
protected

Definition at line 72 of file OctomapInterface.h.

OctomapCollisionChecker* or_octomap::OctomapInterface::m_collisionChecker
protected

Definition at line 69 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::m_isEnabled
protected

Definition at line 68 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::m_isPaused
protected

Definition at line 74 of file OctomapInterface.h.

ros::CallbackQueue or_octomap::OctomapInterface::m_queue
protected

Definition at line 70 of file OctomapInterface.h.

bool or_octomap::OctomapInterface::m_shouldExit
protected

Definition at line 71 of file OctomapInterface.h.


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


or_octomap_plugin
Author(s): Yan Yu
autogenerated on Tue Oct 24 2017 18:02:48