|
| void | camInfoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg) |
| |
| void | fiducial_cb (int id, int direction, double world_diagonal, double x0, double y0, double x1, double y1, double x2, double y2, double x3, double y3) |
| |
| void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
| |
| void | processImage (const sensor_msgs::ImageConstPtr &msg) |
| |
|
| static void | fiducial_announce (void *t, int id, int direction, double world_diagonal, double x0, double y0, double x1, double y1, double x2, double y2, double x3, double y3) |
| |
Definition at line 62 of file fiducial_detect.cpp.
| FiducialsNode::~FiducialsNode |
( |
| ) |
|
| void FiducialsNode::camInfoCallback |
( |
const sensor_msgs::CameraInfo::ConstPtr & |
msg | ) |
|
|
private |
| void FiducialsNode::fiducial_announce |
( |
void * |
t, |
|
|
int |
id, |
|
|
int |
direction, |
|
|
double |
world_diagonal, |
|
|
double |
x0, |
|
|
double |
y0, |
|
|
double |
x1, |
|
|
double |
y1, |
|
|
double |
x2, |
|
|
double |
y2, |
|
|
double |
x3, |
|
|
double |
y3 |
|
) |
| |
|
staticprivate |
| void FiducialsNode::fiducial_cb |
( |
int |
id, |
|
|
int |
direction, |
|
|
double |
world_diagonal, |
|
|
double |
x0, |
|
|
double |
y0, |
|
|
double |
x1, |
|
|
double |
y1, |
|
|
double |
x2, |
|
|
double |
y2, |
|
|
double |
x3, |
|
|
double |
y3 |
|
) |
| |
|
private |
| void FiducialsNode::imageCallback |
( |
const sensor_msgs::ImageConstPtr & |
msg | ) |
|
|
private |
| void FiducialsNode::processImage |
( |
const sensor_msgs::ImageConstPtr & |
msg | ) |
|
|
private |
| std::string FiducialsNode::data_directory |
|
private |
| bool FiducialsNode::estimate_pose |
|
private |
| double FiducialsNode::fiducial_len |
|
private |
| fiducial_msgs::FiducialTransformArray FiducialsNode::fiducialTransformArray |
|
private |
| fiducial_msgs::FiducialArray FiducialsNode::fiducialVertexArray |
|
private |
| int FiducialsNode::frameNum |
|
private |
| bool FiducialsNode::haveCamInfo |
|
private |
| std::string FiducialsNode::last_camera_frame |
|
private |
| int FiducialsNode::last_image_seq |
|
private |
| std::string FiducialsNode::log_file |
|
private |
| RosRpp* FiducialsNode::pose_est |
|
private |
| bool FiducialsNode::processing_image |
|
private |
| bool FiducialsNode::publish_images |
|
private |
| const double FiducialsNode::scale |
|
private |
| bool FiducialsNode::undistort_points |
|
private |
| boost::thread* FiducialsNode::update_thread |
|
private |
The documentation for this class was generated from the following file: