KidnappedNode Class Reference

List of all members.

Public Member Functions

void addToSamplePoses (const tf::Transform &base_in_map, const tf::Transform &camera_in_base)
void collectImages (int n)
 Collect n images evenly spaced around the robot.
void imageCb (const sensor_msgs::ImageConstPtr &l_image, const sensor_msgs::CameraInfoConstPtr &l_cam_info, const sensor_msgs::ImageConstPtr &r_image, const sensor_msgs::CameraInfoConstPtr &r_cam_info)
 KidnappedNode (const std::string &db_file, const std::string &vocab_tree_file, const std::string &vocab_weights_file, const std::string &calonder_trees_file)
void loadDbSamplePoses ()
bool localizeCb (kidnapped_robot::RecognizePlace::Request &request, kidnapped_robot::RecognizePlace::Response &response)
void lookAt (double x, double y, double z)
 Points the camera frame at a point in the target frame.
void poseCb (const geometry_msgs::PoseWithCovarianceStamped &pose_estimate)
void publishSamplePoses ()
void subscribeStereo ()
void unsubscribeStereo ()

Private Attributes

int best_inliers_
tf::Stamped< tf::Pose > best_pose_
image_geometry::StereoCameraModel cam_model_
std::string camera_optical_frame_
bool collect_new_data_
double distance_threshold_
frame_common::FrameProc frame_processor_
double head_target_z_
image_transport::Publisher image_match_pub_
image_transport::Publisher image_sample_pub_
ros::Publisher initial_pose_pub_
ros::Publisher initial_pose_viz_pub_
boost::scoped_ptr
< image_transport::ImageTransport > 
it_
sensor_msgs::CvBridge l_bridge_
image_transport::SubscriberFilter l_image_sub_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
l_info_sub_
ros::Subscriber localization_sub_
std::string map_frame_
ros::ServiceClient mux_client_
ros::NodeHandle nh_
int num_samples_
kidnapped_robot::PlaceDatabase place_db_
PointHeadClient point_head_client_
pe::PoseEstimator3d pose_estimator_
int pr_inliers_
ros::ServiceServer pr_server_
sensor_msgs::CvBridge r_bridge_
image_transport::SubscriberFilter r_image_sub_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
r_info_sub_
boost::condition_variable sample_cond_
boost::mutex sample_mutex_
ros::Publisher sample_pose_pub_
geometry_msgs::PoseArray sample_poses_
boost::scoped_ptr
< ros::AsyncSpinner > 
spinner_
ros::CallbackQueue stereo_cb_queue_
ros::NodeHandle stereo_nh_
message_filters::TimeSynchronizer
< sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::Image,
sensor_msgs::CameraInfo > 
sync_
bool take_sample_
std::string target_frame_
tf::TransformListener tf_

Detailed Description

Definition at line 28 of file kidnapped_node.cpp.


Constructor & Destructor Documentation

KidnappedNode::KidnappedNode ( const std::string &  db_file,
const std::string &  vocab_tree_file,
const std::string &  vocab_weights_file,
const std::string &  calonder_trees_file 
) [inline]

Definition at line 81 of file kidnapped_node.cpp.


Member Function Documentation

void KidnappedNode::addToSamplePoses ( const tf::Transform &  base_in_map,
const tf::Transform &  camera_in_base 
) [inline]

Definition at line 423 of file kidnapped_node.cpp.

void KidnappedNode::collectImages ( int  n  )  [inline]

Collect n images evenly spaced around the robot.

Definition at line 248 of file kidnapped_node.cpp.

void KidnappedNode::imageCb ( const sensor_msgs::ImageConstPtr &  l_image,
const sensor_msgs::CameraInfoConstPtr &  l_cam_info,
const sensor_msgs::ImageConstPtr &  r_image,
const sensor_msgs::CameraInfoConstPtr &  r_cam_info 
) [inline]

Todo:
Don't have to look up base_in_map every time, but arguably more robust this way
Todo:
Make parameterizable
Todo:
Rename to base_to_camera, etc.

Definition at line 298 of file kidnapped_node.cpp.

void KidnappedNode::loadDbSamplePoses (  )  [inline]

Definition at line 138 of file kidnapped_node.cpp.

bool KidnappedNode::localizeCb ( kidnapped_robot::RecognizePlace::Request request,
kidnapped_robot::RecognizePlace::Response response 
) [inline]

Definition at line 436 of file kidnapped_node.cpp.

void KidnappedNode::lookAt ( double  x,
double  y,
double  z 
) [inline]

Points the camera frame at a point in the target frame.

Definition at line 183 of file kidnapped_node.cpp.

void KidnappedNode::poseCb ( const geometry_msgs::PoseWithCovarianceStamped &  pose_estimate  )  [inline]

Definition at line 213 of file kidnapped_node.cpp.

void KidnappedNode::publishSamplePoses (  )  [inline]

Definition at line 159 of file kidnapped_node.cpp.

void KidnappedNode::subscribeStereo (  )  [inline]

Definition at line 166 of file kidnapped_node.cpp.

void KidnappedNode::unsubscribeStereo (  )  [inline]

Definition at line 174 of file kidnapped_node.cpp.


Member Data Documentation

Definition at line 70 of file kidnapped_node.cpp.

tf::Stamped<tf::Pose> KidnappedNode::best_pose_ [private]

Definition at line 69 of file kidnapped_node.cpp.

image_geometry::StereoCameraModel KidnappedNode::cam_model_ [private]

Definition at line 74 of file kidnapped_node.cpp.

std::string KidnappedNode::camera_optical_frame_ [private]

Definition at line 77 of file kidnapped_node.cpp.

Definition at line 62 of file kidnapped_node.cpp.

Definition at line 61 of file kidnapped_node.cpp.

frame_common::FrameProc KidnappedNode::frame_processor_ [private]

Definition at line 57 of file kidnapped_node.cpp.

Definition at line 78 of file kidnapped_node.cpp.

image_transport::Publisher KidnappedNode::image_match_pub_ [private]

Definition at line 45 of file kidnapped_node.cpp.

image_transport::Publisher KidnappedNode::image_sample_pub_ [private]

Definition at line 45 of file kidnapped_node.cpp.

ros::Publisher KidnappedNode::initial_pose_pub_ [private]

Definition at line 48 of file kidnapped_node.cpp.

ros::Publisher KidnappedNode::initial_pose_viz_pub_ [private]

Definition at line 49 of file kidnapped_node.cpp.

boost::scoped_ptr<image_transport::ImageTransport> KidnappedNode::it_ [private]

Definition at line 33 of file kidnapped_node.cpp.

sensor_msgs::CvBridge KidnappedNode::l_bridge_ [private]

Definition at line 73 of file kidnapped_node.cpp.

image_transport::SubscriberFilter KidnappedNode::l_image_sub_ [private]

Definition at line 37 of file kidnapped_node.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> KidnappedNode::l_info_sub_ [private]

Definition at line 38 of file kidnapped_node.cpp.

ros::Subscriber KidnappedNode::localization_sub_ [private]

Definition at line 41 of file kidnapped_node.cpp.

std::string KidnappedNode::map_frame_ [private]

Definition at line 77 of file kidnapped_node.cpp.

ros::ServiceClient KidnappedNode::mux_client_ [private]

Definition at line 52 of file kidnapped_node.cpp.

ros::NodeHandle KidnappedNode::nh_ [private]

Definition at line 30 of file kidnapped_node.cpp.

Definition at line 60 of file kidnapped_node.cpp.

Definition at line 56 of file kidnapped_node.cpp.

Definition at line 76 of file kidnapped_node.cpp.

pe::PoseEstimator3d KidnappedNode::pose_estimator_ [private]

Definition at line 58 of file kidnapped_node.cpp.

Definition at line 59 of file kidnapped_node.cpp.

ros::ServiceServer KidnappedNode::pr_server_ [private]

Definition at line 53 of file kidnapped_node.cpp.

sensor_msgs::CvBridge KidnappedNode::r_bridge_ [private]

Definition at line 73 of file kidnapped_node.cpp.

image_transport::SubscriberFilter KidnappedNode::r_image_sub_ [private]

Definition at line 37 of file kidnapped_node.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> KidnappedNode::r_info_sub_ [private]

Definition at line 38 of file kidnapped_node.cpp.

boost::condition_variable KidnappedNode::sample_cond_ [private]
Todo:
Probably could have kept this single-threaded, just do own spin on stereo_cb_queue_

Definition at line 66 of file kidnapped_node.cpp.

boost::mutex KidnappedNode::sample_mutex_ [private]

Definition at line 67 of file kidnapped_node.cpp.

ros::Publisher KidnappedNode::sample_pose_pub_ [private]

Definition at line 47 of file kidnapped_node.cpp.

geometry_msgs::PoseArray KidnappedNode::sample_poses_ [private]

Definition at line 46 of file kidnapped_node.cpp.

boost::scoped_ptr<ros::AsyncSpinner> KidnappedNode::spinner_ [private]

Definition at line 34 of file kidnapped_node.cpp.

ros::CallbackQueue KidnappedNode::stereo_cb_queue_ [private]

Definition at line 31 of file kidnapped_node.cpp.

ros::NodeHandle KidnappedNode::stereo_nh_ [private]

Definition at line 32 of file kidnapped_node.cpp.

message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::CameraInfo> KidnappedNode::sync_ [private]

Definition at line 40 of file kidnapped_node.cpp.

Definition at line 68 of file kidnapped_node.cpp.

std::string KidnappedNode::target_frame_ [private]

Definition at line 77 of file kidnapped_node.cpp.

tf::TransformListener KidnappedNode::tf_ [private]

Definition at line 42 of file kidnapped_node.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs


kidnapped_robot
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 09:51:23 2013