$search

CloudHandler Class Reference

#include <cloud_handler.h>

List of all members.

Public Member Functions

void clear ()
 Clear the cloud stored in this object.
 CloudHandler (ros::NodeHandle *nh, tf::TransformListener *tfl, std::string name, interactive_markers::InteractiveMarkerServer &server, object_manipulator::MechanismInterface &mechanism)
void get (sensor_msgs::PointCloud2 &cloud)
sensor_msgs::PointCloud2 get ()
 Get the cloud stored in this object.
void refresh (const std::string &topic)
void refresh ()
 Refresh the cloud stored in this object.
 ~CloudHandler ()

Private Types

typedef
interactive_markers::MenuHandler 
MenuHandler

Private Member Functions

void leftClickPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void makeMarker (float size)
void makeMenu ()
void menuFocus (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void menuPoint (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void pickup (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void saveCloudAndNormals ()

Private Attributes

pcl::PointCloud< pcl::Normal >::Ptr cloud_normals_
pcl::PointCloud< PointT >::Ptr cloud_pts_
actionlib::SimpleActionClient
< point_cloud_server::StoreCloudAction
cloud_server_client_
bool double_menu_
std::string head_pointing_frame_
interactive_markers::InteractiveMarkerServermarker_server_
object_manipulator::MechanismInterfacemechanism_
interactive_markers::MenuHandler menu_handler_
sensor_msgs::PointCloud2 msg_cloud_
std::string name_
ros::NodeHandlenh_
ros::Publisher pub_focus_
ros::Publisher pub_left_click_
ros::Publisher pub_refresh_flag_
ros::Publisher pub_right_click_
tf::TransformListenertfl_
std::string topic_
pcl::KdTreeFLANN< PointT >::Ptr tree_
double voxel_size_

Detailed Description

Definition at line 50 of file cloud_handler.h.


Member Typedef Documentation

Definition at line 72 of file cloud_handler.h.


Constructor & Destructor Documentation

CloudHandler::CloudHandler ( ros::NodeHandle nh,
tf::TransformListener tfl,
std::string  name,
interactive_markers::InteractiveMarkerServer server,
object_manipulator::MechanismInterface mechanism 
)

Definition at line 57 of file cloud_handler.cpp.

CloudHandler::~CloudHandler (  ) 

Definition at line 84 of file cloud_handler.cpp.


Member Function Documentation

void CloudHandler::clear ( void   ) 

Clear the cloud stored in this object.

Definition at line 361 of file cloud_handler.cpp.

void CloudHandler::get ( sensor_msgs::PointCloud2 cloud  ) 

Definition at line 302 of file cloud_handler.cpp.

sensor_msgs::PointCloud2 CloudHandler::get (  ) 

Get the cloud stored in this object.

Definition at line 307 of file cloud_handler.cpp.

void CloudHandler::leftClickPoint ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [private]

Definition at line 106 of file cloud_handler.cpp.

void CloudHandler::makeMarker ( float  size  )  [private]

Definition at line 367 of file cloud_handler.cpp.

void CloudHandler::makeMenu (  )  [private]

Definition at line 89 of file cloud_handler.cpp.

void CloudHandler::menuFocus ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [private]

Definition at line 132 of file cloud_handler.cpp.

void CloudHandler::menuPoint ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [private]

Definition at line 160 of file cloud_handler.cpp.

void CloudHandler::pickup ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  )  [private]
void CloudHandler::refresh ( const std::string &  topic  ) 

Definition at line 318 of file cloud_handler.cpp.

void CloudHandler::refresh (  ) 

Refresh the cloud stored in this object.

Definition at line 312 of file cloud_handler.cpp.

void CloudHandler::saveCloudAndNormals (  )  [private]

Definition at line 252 of file cloud_handler.cpp.


Member Data Documentation

pcl::PointCloud<pcl::Normal>::Ptr CloudHandler::cloud_normals_ [private]

Definition at line 96 of file cloud_handler.h.

pcl::PointCloud<PointT>::Ptr CloudHandler::cloud_pts_ [private]

Definition at line 95 of file cloud_handler.h.

Definition at line 102 of file cloud_handler.h.

Definition at line 99 of file cloud_handler.h.

std::string CloudHandler::head_pointing_frame_ [private]

Definition at line 103 of file cloud_handler.h.

Definition at line 91 of file cloud_handler.h.

Definition at line 101 of file cloud_handler.h.

Definition at line 92 of file cloud_handler.h.

Definition at line 94 of file cloud_handler.h.

std::string CloudHandler::name_ [private]

Definition at line 86 of file cloud_handler.h.

Definition at line 87 of file cloud_handler.h.

Definition at line 88 of file cloud_handler.h.

Definition at line 88 of file cloud_handler.h.

Definition at line 88 of file cloud_handler.h.

Definition at line 88 of file cloud_handler.h.

Definition at line 89 of file cloud_handler.h.

std::string CloudHandler::topic_ [private]

Definition at line 86 of file cloud_handler.h.

pcl::KdTreeFLANN<PointT>::Ptr CloudHandler::tree_ [private]

Definition at line 97 of file cloud_handler.h.

double CloudHandler::voxel_size_ [private]

Definition at line 98 of file cloud_handler.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_marker_control
Author(s): Adam Leeper
autogenerated on Tue Mar 5 14:40:32 2013