#include <handeye_log.h>
Definition at line 54 of file handeye_log.h.
typedef pcl::PointWithRange HandeyeLog::Point [private] |
Definition at line 80 of file handeye_log.h.
typedef pcl::PointCloud<Point> HandeyeLog::PointCloud [private] |
Definition at line 81 of file handeye_log.h.
Definition at line 121 of file handeye_log.cpp.
Definition at line 276 of file handeye_log.cpp.
void HandeyeLog::iimg_sub_callback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [private] |
Definition at line 368 of file handeye_log.cpp.
void HandeyeLog::pcl2_sub_callback | ( | const sensor_msgs::PointCloud2ConstPtr & | msg | ) | [private] |
Definition at line 338 of file handeye_log.cpp.
bool HandeyeLog::srv_callback | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) | [private] |
Definition at line 407 of file handeye_log.cpp.
void * HandeyeLog::store_dimg_thread | ( | void * | param | ) | [static, protected] |
Definition at line 510 of file handeye_log.cpp.
void * HandeyeLog::store_iimg_thread | ( | void * | param | ) | [static, protected] |
Definition at line 555 of file handeye_log.cpp.
void * HandeyeLog::store_ipng_thread | ( | void * | param | ) | [static, protected] |
Definition at line 601 of file handeye_log.cpp.
void * HandeyeLog::store_mpcl2_thread | ( | void * | param | ) | [static, protected] |
Definition at line 469 of file handeye_log.cpp.
void * HandeyeLog::store_tf_pattern_thread | ( | void * | param | ) | [static, protected] |
Definition at line 687 of file handeye_log.cpp.
void * HandeyeLog::store_tf_robot_inverse_thread | ( | void * | param | ) | [static, protected] |
Definition at line 723 of file handeye_log.cpp.
void * HandeyeLog::store_tf_robot_thread | ( | void * | param | ) | [static, protected] |
Definition at line 650 of file handeye_log.cpp.
void HandeyeLog::tf_pattern_sub_callback | ( | const geometry_msgs::PoseStampedConstPtr & | msg | ) | [private] |
Definition at line 400 of file handeye_log.cpp.
void HandeyeLog::tf_robot_sub_callback | ( | const geometry_msgs::PoseStampedConstPtr & | msg | ) | [private] |
Definition at line 393 of file handeye_log.cpp.
boost::circular_buffer<PointCloud, Eigen::aligned_allocator<PointCloud> > HandeyeLog::cloudBuffer_ [private] |
Definition at line 82 of file handeye_log.h.
cv_bridge::CvImagePtr HandeyeLog::cv_ptr_ [private] |
Definition at line 85 of file handeye_log.h.
std::string HandeyeLog::dimg_event_off_id_ [private] |
Definition at line 123 of file handeye_log.h.
std::string HandeyeLog::dimg_event_on_id_ [private] |
Definition at line 122 of file handeye_log.h.
std::string HandeyeLog::dimg_event_stop_id_ [private] |
Definition at line 124 of file handeye_log.h.
std::string HandeyeLog::dimg_thread_id_ [private] |
Definition at line 139 of file handeye_log.h.
CEventServer* HandeyeLog::event_server [private] |
Definition at line 147 of file handeye_log.h.
bool HandeyeLog::flag_dimg [private] |
Definition at line 62 of file handeye_log.h.
bool HandeyeLog::flag_iimg [private] |
Definition at line 60 of file handeye_log.h.
bool HandeyeLog::flag_ipng [private] |
Definition at line 61 of file handeye_log.h.
bool HandeyeLog::flag_mpcl2 [private] |
Definition at line 63 of file handeye_log.h.
bool HandeyeLog::flag_tf_pattern [private] |
Definition at line 59 of file handeye_log.h.
bool HandeyeLog::flag_tf_robot [private] |
Definition at line 58 of file handeye_log.h.
bool HandeyeLog::flag_tf_robot_inverse [private] |
Definition at line 64 of file handeye_log.h.
int HandeyeLog::idx [private] |
Definition at line 67 of file handeye_log.h.
boost::circular_buffer<cv_bridge::CvImagePtr> HandeyeLog::iimageBuffer_ [private] |
Definition at line 86 of file handeye_log.h.
std::string HandeyeLog::iimg_event_off_id_ [private] |
Definition at line 117 of file handeye_log.h.
std::string HandeyeLog::iimg_event_on_id_ [private] |
Definition at line 116 of file handeye_log.h.
std::string HandeyeLog::iimg_event_stop_id_ [private] |
Definition at line 118 of file handeye_log.h.
ros::Subscriber HandeyeLog::iimg_sub [private] |
Definition at line 105 of file handeye_log.h.
std::string HandeyeLog::iimg_thread_id_ [private] |
Definition at line 137 of file handeye_log.h.
std::ofstream HandeyeLog::img_depth_ [private] |
Definition at line 92 of file handeye_log.h.
std::ofstream HandeyeLog::img_intensity_ [private] |
Definition at line 93 of file handeye_log.h.
sensor_msgs::Image::ConstPtr HandeyeLog::intens_image_ [private] |
Definition at line 88 of file handeye_log.h.
std::string HandeyeLog::ipng_event_off_id_ [private] |
Definition at line 120 of file handeye_log.h.
std::string HandeyeLog::ipng_event_on_id_ [private] |
Definition at line 119 of file handeye_log.h.
std::string HandeyeLog::ipng_event_stop_id_ [private] |
Definition at line 121 of file handeye_log.h.
std::string HandeyeLog::ipng_thread_id_ [private] |
Definition at line 138 of file handeye_log.h.
std::ofstream HandeyeLog::matlab_file_ [private] |
Definition at line 90 of file handeye_log.h.
std::ofstream HandeyeLog::matlab_file_seq [private] |
Definition at line 91 of file handeye_log.h.
std::string HandeyeLog::mpcl2_event_off_id_ [private] |
Definition at line 114 of file handeye_log.h.
std::string HandeyeLog::mpcl2_event_on_id_ [private] |
Definition at line 113 of file handeye_log.h.
std::string HandeyeLog::mpcl2_event_stop_id_ [private] |
Definition at line 115 of file handeye_log.h.
std::string HandeyeLog::mpcl2_thread_id_ [private] |
Definition at line 136 of file handeye_log.h.
sensor_msgs::PointCloud2ConstPtr* HandeyeLog::msg_ [private] |
Definition at line 71 of file handeye_log.h.
int HandeyeLog::nc [private] |
Definition at line 69 of file handeye_log.h.
ros::NodeHandle HandeyeLog::nh [private] |
Definition at line 101 of file handeye_log.h.
int HandeyeLog::nr [private] |
Definition at line 68 of file handeye_log.h.
int HandeyeLog::num_captures_ [private] |
Definition at line 65 of file handeye_log.h.
ros::Subscriber HandeyeLog::pcl2_sub [private] |
Definition at line 104 of file handeye_log.h.
int HandeyeLog::pcl_type_ [private] |
Definition at line 72 of file handeye_log.h.
pcl::PointCloud<pcl::PointXYZ> HandeyeLog::pcl_xyz_ [private] |
Definition at line 84 of file handeye_log.h.
pcl::PointCloud<pcl::PointWithRange> HandeyeLog::pcl_xyzr_ [private] |
Definition at line 74 of file handeye_log.h.
pcl::PointCloud<pcl::PointXYZRGB> HandeyeLog::pcl_xyzrgb_ [private] |
Definition at line 73 of file handeye_log.h.
sensor_msgs::PointCloud2 HandeyeLog::pcl_xyzri_ [private] |
Definition at line 77 of file handeye_log.h.
ros::ServiceServer HandeyeLog::srv [private] |
Definition at line 110 of file handeye_log.h.
tf::Transform HandeyeLog::tf_pattern_ [private] |
Definition at line 98 of file handeye_log.h.
std::string HandeyeLog::tf_pattern_event_off_id_ [private] |
Definition at line 129 of file handeye_log.h.
std::string HandeyeLog::tf_pattern_event_on_id_ [private] |
Definition at line 128 of file handeye_log.h.
std::string HandeyeLog::tf_pattern_event_stop_id_ [private] |
Definition at line 130 of file handeye_log.h.
std::ofstream HandeyeLog::tf_pattern_file_ [private] |
Definition at line 95 of file handeye_log.h.
ros::Subscriber HandeyeLog::tf_pattern_sub [private] |
Definition at line 107 of file handeye_log.h.
std::string HandeyeLog::tf_pattern_thread_id_ [private] |
Definition at line 141 of file handeye_log.h.
tf::Transform HandeyeLog::tf_robot_ [private] |
Definition at line 97 of file handeye_log.h.
std::string HandeyeLog::tf_robot_event_off_id_ [private] |
Definition at line 126 of file handeye_log.h.
std::string HandeyeLog::tf_robot_event_on_id_ [private] |
Definition at line 125 of file handeye_log.h.
std::string HandeyeLog::tf_robot_event_stop_id_ [private] |
Definition at line 127 of file handeye_log.h.
std::ofstream HandeyeLog::tf_robot_file_ [private] |
Definition at line 94 of file handeye_log.h.
std::string HandeyeLog::tf_robot_inverse_event_off_id_ [private] |
Definition at line 132 of file handeye_log.h.
std::string HandeyeLog::tf_robot_inverse_event_on_id_ [private] |
Definition at line 131 of file handeye_log.h.
std::string HandeyeLog::tf_robot_inverse_event_stop_id_ [private] |
Definition at line 133 of file handeye_log.h.
std::string HandeyeLog::tf_robot_inverse_thread_id_ [private] |
Definition at line 142 of file handeye_log.h.
ros::Subscriber HandeyeLog::tf_robot_sub [private] |
Definition at line 106 of file handeye_log.h.
std::string HandeyeLog::tf_robot_thread_id_ [private] |
Definition at line 140 of file handeye_log.h.
CThreadServer* HandeyeLog::thread_server [private] |
Definition at line 145 of file handeye_log.h.