00001 #include <ros/ros.h>
00002 #include <actionlib/server/simple_action_server.h>
00003 #include <pr2_plugs_msgs/VisionPlugDetectionAction.h>
00004 #include <image_transport/image_transport.h>
00005 #include <tf/transform_listener.h>
00006
00007 #include <checkerboard_pose_estimation/ros_detector.h>
00008
00009 class DetectPlugAction
00010 {
00011 public:
00012 DetectPlugAction(const std::string& name)
00013 : it_(nh_),
00014 as_(nh_, name),
00015 name_(name)
00016 {
00017
00018 if (!detector_.initFromParameters()) {
00019 ROS_FATAL("%s: One or more required parameters not set, shutting down", name_.c_str());
00020 nh_.shutdown();
00021 return;
00022 }
00023
00024
00025 as_.registerGoalCallback(boost::bind(&DetectPlugAction::goalCb, this));
00026 as_.registerPreemptCallback(boost::bind(&DetectPlugAction::preemptCb, this));
00027
00028 ROS_INFO("Finished registering callbacks");
00029 }
00030
00031 void timeoutCb(const ros::TimerEvent& e)
00032 {
00033 if(sub_.getNumPublishers() == 0)
00034 ROS_INFO("%s: Aborted, there are no publishers on goal topic.", name_.c_str());
00035 else
00036 ROS_INFO("%s: Aborted, there are publishers on goal topic, but detection took too long.", name_.c_str());
00037
00038 sub_.shutdown();
00039 as_.setAborted();
00040 }
00041
00042 void goalCb()
00043 {
00044 ROS_INFO("%s: Received new goal", name_.c_str());
00045
00046
00047 typedef boost::shared_ptr<const pr2_plugs_msgs::VisionPlugDetectionGoal> GoalPtr;
00048 GoalPtr goal = as_.acceptNewGoal();
00050 typedef checkerboard_pose_estimation::Detector Side;
00051 detector_.getDetector().setOriginSide(goal->origin_on_right ? Side::RIGHT : Side::LEFT);
00052 tf::poseStampedMsgToTF(goal->prior, plug_prior_);
00053
00054
00055 ros::Duration(1.0).sleep();
00056 std::string image_topic = goal->camera_name + "/image_rect";
00057 sub_ = it_.subscribeCamera(image_topic, 1, &DetectPlugAction::detectCb, this);
00058
00059
00060 pub_timer_ = nh_.createTimer(tf_listener_.getCacheLength() - ros::Duration(1.0), boost::bind(&DetectPlugAction::timeoutCb, this, _1), true);
00061 }
00062
00063 void preemptCb()
00064 {
00065 ROS_INFO("%s: Preempted", name_.c_str());
00066 as_.setPreempted();
00067 pub_timer_.stop();
00068 sub_.shutdown();
00069 }
00070
00071 void detectCb(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info_msg)
00072 {
00073 if (!as_.isActive()) return;
00074
00075 ROS_INFO("%s: Received image, performing detection", name_.c_str());
00076
00077 tf::Stamped<tf::Pose> plug_pose;
00078 if (detector_.detectObject(image_msg, info_msg, plug_prior_, tf_listener_, plug_pose)) {
00079
00080 pr2_plugs_msgs::VisionPlugDetectionResult result;
00081 tf::poseStampedTFToMsg(plug_pose, result.plug_pose);
00082 as_.setSucceeded(result);
00083 pub_timer_.stop();
00084
00085
00086 sub_.shutdown();
00087 }
00088 }
00089
00090 protected:
00091 ros::NodeHandle nh_;
00092 image_transport::ImageTransport it_;
00093 actionlib::SimpleActionServer<pr2_plugs_msgs::VisionPlugDetectionAction> as_;
00094 std::string name_;
00095 image_transport::CameraSubscriber sub_;
00096 tf::TransformListener tf_listener_;
00097 tf::Stamped<tf::Pose> plug_prior_;
00098 checkerboard_pose_estimation::RosDetector detector_;
00099 ros::Timer pub_timer_;
00100 };
00101
00102 int main(int argc, char** argv)
00103 {
00104 ros::init(argc, argv, "vision_detect_plug");
00105 DetectPlugAction action(ros::this_node::getName());
00106 ros::spin();
00107
00108 return 0;
00109 }