#include <comthread.h>
Public Slots | |
void | changedBoxSize (double) |
void | createKinectModel (QDir &parent_dir, const QString &model_name) |
void | createRe_visionModel (QDir &parent_dir, const QString &model_name) |
void | markerSizeChanged (double value) |
void | markerSpacingChanged (double value) |
void | maxScanNumberChanged (int) |
void | recording (bool startstop) |
void | removeCloud (QStringList) |
void | reset () |
void | selectCloud (QStringList) |
Signals | |
void | addStatusMessage (QString) |
void | newCloudReceived (QString) |
Public Member Functions | |
ComThread (QObject *parent=0) | |
bool | createPreview (QDir &model_dir) |
void | loadPointCloud (const QString &filename) |
void | pointCloudReceived (const sensor_msgs::PointCloud2ConstPtr &pcl_msg) |
virtual | ~ComThread () |
Protected Member Functions | |
int | addPointCloud (boost::shared_ptr< pcl::PointCloud< PointType > > cloud) |
void | getMergedPointCloud (pcl::PointCloud< PointType > &merged_pcl) |
void | run () |
void | saveFaces (QDir) |
void | saveMergedPCL (QString) |
Protected Attributes | |
pcl::visualization::CloudViewer * | cloudViewer |
bool | isRecording |
unsigned int | max_pointclouds |
maximum number of pointclouds to keep in memory | |
QMutex | mutex |
int | npoints |
std::map< int, boost::shared_ptr < pcl::PointCloud< PointType > > > | pcls |
ros::Subscriber | sub |
tf::TransformListener | tf |
Main ROS communication thread. Also receives and stores point clouds.
Definition at line 71 of file comthread.h.
ComThread::ComThread | ( | QObject * | parent = 0 | ) | [explicit] |
Definition at line 59 of file comthread.cpp.
ComThread::~ComThread | ( | ) | [virtual] |
Definition at line 71 of file comthread.cpp.
int ComThread::addPointCloud | ( | boost::shared_ptr< pcl::PointCloud< PointType > > | cloud | ) | [protected] |
Add a pointcloud to the storage and to the visualization.
cloud | the cloud to add |
Definition at line 235 of file comthread.cpp.
void ComThread::addStatusMessage | ( | QString | ) | [signal] |
Add a status message to the message log QTextEdit in the UI.
QString | message to show |
void ComThread::changedBoxSize | ( | double | size | ) | [slot] |
Updates the new bounding box size in the cloud viewer.
double | new bounding box size |
Definition at line 347 of file comthread.cpp.
void ComThread::createKinectModel | ( | QDir & | parent_dir, |
const QString & | model_name | ||
) | [slot] |
Export a kinect object model (i.e. a set of dense .pcd files)
parent_dir | directory in which to store the model |
model_name | name of the model |
Definition at line 379 of file comthread.cpp.
bool ComThread::createPreview | ( | QDir & | model_dir | ) |
Create a preview image of the object. It gets saved in model_dir.
model_dir | target directory for the image file |
Definition at line 408 of file comthread.cpp.
void ComThread::createRe_visionModel | ( | QDir & | parent_dir, |
const QString & | model_name | ||
) | [slot] |
Export an object recognition model compatible with re_vision.
parent_dir | directory in which to store the model |
model_name | name of the model |
Definition at line 364 of file comthread.cpp.
void ComThread::getMergedPointCloud | ( | pcl::PointCloud< PointType > & | merged_pcl | ) | [protected] |
Merge all recorded point clouds.
merged_pcl | output parameter for the merged point cloud |
Definition at line 312 of file comthread.cpp.
void ComThread::loadPointCloud | ( | const QString & | filename | ) |
Load and add a pointcloud from a .pcd file.
filename | path to the pcd file |
Definition at line 224 of file comthread.cpp.
void ComThread::markerSizeChanged | ( | double | value | ) | [slot] |
User changed edge length of AR markers.
value | New AR marker size. |
Definition at line 396 of file comthread.cpp.
void ComThread::markerSpacingChanged | ( | double | value | ) | [slot] |
User changed spacing of AR markers.
value | New AR marker spacing. |
Definition at line 402 of file comthread.cpp.
void ComThread::maxScanNumberChanged | ( | int | value | ) | [slot] |
The user changed the number of maximum scans in the UI.
int | new maximum number of scans |
Definition at line 392 of file comthread.cpp.
void ComThread::newCloudReceived | ( | QString | ) | [signal] |
Signals that a new point cloud was received
QString | the name of the cloud in the viewer or "-" if the cloud was not recorded |
void ComThread::pointCloudReceived | ( | const sensor_msgs::PointCloud2ConstPtr & | pcl_msg | ) |
Point cloud callback
pcl_msg | the received point cloud message |
Definition at line 104 of file comthread.cpp.
void ComThread::recording | ( | bool | startstop | ) | [slot] |
Definition at line 83 of file comthread.cpp.
void ComThread::removeCloud | ( | QStringList | ids | ) | [slot] |
Removes the given point clouds.
QStringList | the names of the point clouds to remove |
Definition at line 257 of file comthread.cpp.
void ComThread::reset | ( | ) | [slot] |
Resets the cloud viewer and removes all recorded point clouds.
Definition at line 87 of file comthread.cpp.
void ComThread::run | ( | void | ) | [protected] |
Definition at line 75 of file comthread.cpp.
void ComThread::saveFaces | ( | QDir | model_dir | ) | [protected] |
Store all point clouds in a directory.
QDir | target directory |
Definition at line 337 of file comthread.cpp.
void ComThread::saveMergedPCL | ( | QString | filename | ) | [protected] |
Merge all point clouds and save them in a pcd file.
QString | filename |
Definition at line 330 of file comthread.cpp.
void ComThread::selectCloud | ( | QStringList | newSelections | ) | [slot] |
Selects the given point clouds.
the | names of the point clouds to select |
Definition at line 270 of file comthread.cpp.
pcl::visualization::CloudViewer* ComThread::cloudViewer [protected] |
Definition at line 194 of file comthread.h.
bool ComThread::isRecording [protected] |
Definition at line 191 of file comthread.h.
unsigned int ComThread::max_pointclouds [protected] |
maximum number of pointclouds to keep in memory
Definition at line 198 of file comthread.h.
QMutex ComThread::mutex [protected] |
Definition at line 195 of file comthread.h.
int ComThread::npoints [protected] |
Definition at line 193 of file comthread.h.
std::map<int, boost::shared_ptr< pcl::PointCloud<PointType> > > ComThread::pcls [protected] |
Definition at line 192 of file comthread.h.
ros::Subscriber ComThread::sub [protected] |
Definition at line 190 of file comthread.h.
tf::TransformListener ComThread::tf [protected] |
Definition at line 189 of file comthread.h.