#include <Perception3d.h>
Definition at line 52 of file Perception3d.h.
void Perception3d::bottleCallback | ( | const ias_table_msgs::TableCluster::ConstPtr & | msg | ) | [static] |
Definition at line 267 of file Perception3d.cpp.
void Perception3d::fridgePlaneCloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [static] |
Definition at line 333 of file Perception3d.cpp.
tf::Stamped< tf::Pose > Perception3d::getBottlePose | ( | ) | [static] |
Definition at line 282 of file Perception3d.cpp.
tf::Stamped< tf::Pose > Perception3d::getFridgePlaneCenterPose | ( | ) | [static] |
Definition at line 356 of file Perception3d.cpp.
tf::Stamped< tf::Pose > Perception3d::getHandlePoseFromLaser | ( | int | pos | ) | [static] |
Definition at line 67 of file Perception3d.cpp.
tf::Stamped< tf::Pose > Perception3d::getHandlePoseFromLaser | ( | tf::Stamped< tf::Pose > | hint, |
double | wait = -1 |
||
) | [static] |
Definition at line 182 of file Perception3d.cpp.
void Perception3d::handleCallback | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) | [static] |
Definition at line 51 of file Perception3d.cpp.
void Perception3d::handleCloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) | [static] |
Definition at line 125 of file Perception3d.cpp.
ros::Time Perception3d::cloud_time [static] |
Definition at line 62 of file Perception3d.h.
Definition at line 56 of file Perception3d.h.
boost::mutex Perception3d::handle_mutex [static] |
Definition at line 57 of file Perception3d.h.
btVector3 Perception3d::handleHint [static] |
Definition at line 60 of file Perception3d.h.
double Perception3d::handleMinDist [static] |
Definition at line 64 of file Perception3d.h.
std::vector< tf::Stamped< tf::Pose > * > Perception3d::handlePoses = *(new std::vector<tf::Stamped<tf::Pose> *> ()) [static] |
Definition at line 65 of file Perception3d.h.
btVector3 Perception3d::handleResult [static] |
Definition at line 61 of file Perception3d.h.
PointCloudT Perception3d::lastCloud [static] |
Definition at line 59 of file Perception3d.h.
boost::mutex Perception3d::plane_mutex [static] |
Definition at line 58 of file Perception3d.h.
std::vector< tf::Stamped< tf::Pose > * > Perception3d::planePoses = *(new std::vector<tf::Stamped<tf::Pose> *> ()) [static] |
Definition at line 66 of file Perception3d.h.
ros::Time Perception3d::query_time [static] |
Definition at line 63 of file Perception3d.h.