Public Member Functions | Protected Attributes
checkerboard_pose_estimation::RosDetector Class Reference

#include <ros_detector.h>

List of all members.

Public Member Functions

bool detectObject (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info_msg, const tf::Stamped< tf::Pose > &target_prior, const tf::Transformer &transformer, tf::Stamped< tf::Pose > &target_pose)
DetectorgetDetector ()
const DetectorgetDetector () const
visual_pose_estimation::PoseEstimatorgetPoseEstimator ()
const
visual_pose_estimation::PoseEstimator
getPoseEstimator () const
bool initFromParameters (const ros::NodeHandle &nh=ros::NodeHandle("~"))
void publishDisplayImage (const cv::Mat &source, const std::vector< cv::Point2f > &corners, bool success)
 RosDetector (const std::string &name=ros::this_node::getName())

Protected Attributes

image_geometry::PinholeCameraModel cam_model_
Detector detector_
sensor_msgs::Image display_img_
cv::Mat display_img_cv_
image_transport::Publisher display_pub_
image_transport::ImageTransport it_
ros::Publisher marker_pub_
std::string name_
ros::NodeHandle nh_
visual_pose_estimation::PoseEstimator pose_estimator_
tf::Transform target_in_detected_object_
tf::Stamped< tf::Posetarget_prior_
tf::TransformBroadcaster tf_broadcaster_

Detailed Description

Definition at line 13 of file ros_detector.h.


Constructor & Destructor Documentation

Definition at line 6 of file ros_detector.cpp.


Member Function Documentation

bool checkerboard_pose_estimation::RosDetector::detectObject ( const sensor_msgs::ImageConstPtr &  image_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg,
const tf::Stamped< tf::Pose > &  target_prior,
const tf::Transformer transformer,
tf::Stamped< tf::Pose > &  target_pose 
)
Todo:
Publish feedback?

Definition at line 77 of file ros_detector.cpp.

Definition at line 20 of file ros_detector.h.

Definition at line 21 of file ros_detector.h.

Definition at line 23 of file ros_detector.h.

Definition at line 24 of file ros_detector.h.

Definition at line 14 of file ros_detector.cpp.

void checkerboard_pose_estimation::RosDetector::publishDisplayImage ( const cv::Mat &  source,
const std::vector< cv::Point2f > &  corners,
bool  success 
)

Definition at line 124 of file ros_detector.cpp.


Member Data Documentation

Definition at line 46 of file ros_detector.h.

Definition at line 47 of file ros_detector.h.

Definition at line 41 of file ros_detector.h.

Definition at line 42 of file ros_detector.h.

Definition at line 40 of file ros_detector.h.

Definition at line 35 of file ros_detector.h.

Definition at line 43 of file ros_detector.h.

Definition at line 36 of file ros_detector.h.

Definition at line 34 of file ros_detector.h.

Definition at line 48 of file ros_detector.h.

Todo:
Change behavior depending on whether target frame differs from detected object

Definition at line 50 of file ros_detector.h.

Definition at line 51 of file ros_detector.h.

Definition at line 39 of file ros_detector.h.


The documentation for this class was generated from the following files:


checkerboard_pose_estimation
Author(s): Patrick Mihelich
autogenerated on Thu Nov 28 2013 11:46:37