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)
const DetectorgetDetector () const
DetectorgetDetector ()
const
visual_pose_estimation::PoseEstimator & 
getPoseEstimator () const
visual_pose_estimation::PoseEstimator & getPoseEstimator ()
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_
sensor_msgs::CvBridge img_bridge_
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::Pose > target_prior_
tf::TransformBroadcaster tf_broadcaster_

Detailed Description

Definition at line 13 of file ros_detector.h.


Constructor & Destructor Documentation

checkerboard_pose_estimation::RosDetector::RosDetector ( const std::string &  name = ros::this_node::getName()  ) 

Definition at line 4 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 75 of file ros_detector.cpp.

const Detector& checkerboard_pose_estimation::RosDetector::getDetector (  )  const [inline]

Definition at line 18 of file ros_detector.h.

Detector& checkerboard_pose_estimation::RosDetector::getDetector (  )  [inline]

Definition at line 17 of file ros_detector.h.

const visual_pose_estimation::PoseEstimator& checkerboard_pose_estimation::RosDetector::getPoseEstimator (  )  const [inline]

Definition at line 21 of file ros_detector.h.

visual_pose_estimation::PoseEstimator& checkerboard_pose_estimation::RosDetector::getPoseEstimator (  )  [inline]

Definition at line 20 of file ros_detector.h.

bool checkerboard_pose_estimation::RosDetector::initFromParameters ( const ros::NodeHandle &  nh = ros::NodeHandle("~")  ) 

Definition at line 12 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 125 of file ros_detector.cpp.


Member Data Documentation

image_geometry::PinholeCameraModel checkerboard_pose_estimation::RosDetector::cam_model_ [protected]

Definition at line 44 of file ros_detector.h.

Definition at line 45 of file ros_detector.h.

Definition at line 38 of file ros_detector.h.

Definition at line 39 of file ros_detector.h.

image_transport::Publisher checkerboard_pose_estimation::RosDetector::display_pub_ [protected]

Definition at line 37 of file ros_detector.h.

sensor_msgs::CvBridge checkerboard_pose_estimation::RosDetector::img_bridge_ [protected]

Definition at line 43 of file ros_detector.h.

image_transport::ImageTransport checkerboard_pose_estimation::RosDetector::it_ [protected]

Definition at line 32 of file ros_detector.h.

Definition at line 40 of file ros_detector.h.

Definition at line 33 of file ros_detector.h.

Definition at line 31 of file ros_detector.h.

visual_pose_estimation::PoseEstimator checkerboard_pose_estimation::RosDetector::pose_estimator_ [protected]

Definition at line 46 of file ros_detector.h.

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

Definition at line 48 of file ros_detector.h.

Definition at line 49 of file ros_detector.h.

tf::TransformBroadcaster checkerboard_pose_estimation::RosDetector::tf_broadcaster_ [protected]

Definition at line 36 of file ros_detector.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Enumerations Enumerator


checkerboard_pose_estimation
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 10:01:04 2013