Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_perception/robot_to_mask_image.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040
00041 namespace jsk_perception
00042 {
00043 void RobotToMaskImage::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 initSelfMask(*pnh_);
00047 pnh_->param("max_robot_dist", max_robot_dist_, 10.0);
00048 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00049 }
00050
00051 void RobotToMaskImage::subscribe()
00052 {
00053 sub_ = pnh_->subscribe("input/camera_info", 1,
00054 &RobotToMaskImage::infoCallback, this);
00055 }
00056
00057 void RobotToMaskImage::unsubscribe()
00058 {
00059 sub_.shutdown();
00060 }
00061
00062 void RobotToMaskImage::infoCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00063 {
00064 vital_checker_->poke();
00065 if (info_msg) {
00066 image_geometry::PinholeCameraModel model;
00067 model.fromCameraInfo(info_msg);
00068
00069 cv::Mat mask_image = cv::Mat::zeros(info_msg->height, info_msg->width, CV_8UC1);
00070 self_mask_->assumeFrame(info_msg->header);
00071 for (int u = 0; u < info_msg->width; u++) {
00072 for (int v = 0; v < info_msg->height; v++) {
00073
00074 cv::Point uv(u, v);
00075 cv::Point3d p = model.projectPixelTo3dRay(uv);
00076
00077
00078 if (self_mask_->getMaskIntersection(p.x * max_robot_dist_, p.y * max_robot_dist_, p.z * max_robot_dist_) == robot_self_filter::OUTSIDE) {
00079 mask_image.data[mask_image.step * v + mask_image.elemSize() * u] = 255;
00080 }
00081 }
00082 }
00083 pub_.publish(cv_bridge::CvImage(info_msg->header,
00084 sensor_msgs::image_encodings::MONO8,
00085 mask_image).toImageMsg());
00086 }
00087 }
00088
00089 void RobotToMaskImage::initSelfMask(const ros::NodeHandle& pnh)
00090 {
00091
00092 double default_padding, default_scale;
00093 pnh.param("self_see_default_padding", default_padding, 0.01);
00094 pnh.param("self_see_default_scale", default_scale, 1.0);
00095 std::vector<robot_self_filter::LinkInfo> links;
00096
00097 if(!pnh.hasParam("self_see_links")) {
00098 ROS_WARN("No links specified for self filtering.");
00099 } else {
00100 XmlRpc::XmlRpcValue ssl_vals;;
00101 pnh.getParam("self_see_links", ssl_vals);
00102 if(ssl_vals.getType() != XmlRpc::XmlRpcValue::TypeArray) {
00103 ROS_WARN("Self see links need to be an array");
00104 } else {
00105 if(ssl_vals.size() == 0) {
00106 ROS_WARN("No values in self see links array");
00107 } else {
00108 for(int i = 0; i < ssl_vals.size(); i++) {
00109 robot_self_filter::LinkInfo li;
00110 if(ssl_vals[i].getType() != XmlRpc::XmlRpcValue::TypeStruct) {
00111 ROS_WARN("Self see links entry %d is not a structure. Stopping processing of self see links",i);
00112 break;
00113 }
00114 if(!ssl_vals[i].hasMember("name")) {
00115 ROS_WARN("Self see links entry %d has no name. Stopping processing of self see links",i);
00116 break;
00117 }
00118 li.name = std::string(ssl_vals[i]["name"]);
00119 if(!ssl_vals[i].hasMember("padding")) {
00120 ROS_DEBUG("Self see links entry %d has no padding. Assuming default padding of %g",i,default_padding);
00121 li.padding = default_padding;
00122 } else {
00123 li.padding = ssl_vals[i]["padding"];
00124 }
00125 if(!ssl_vals[i].hasMember("scale")) {
00126 ROS_DEBUG("Self see links entry %d has no scale. Assuming default scale of %g",i,default_scale);
00127 li.scale = default_scale;
00128 } else {
00129 li.scale = ssl_vals[i]["scale"];
00130 }
00131 links.push_back(li);
00132 }
00133 }
00134 }
00135 }
00136 self_mask_ = boost::shared_ptr<robot_self_filter::SelfMask<pcl::PointXYZ> >(new robot_self_filter::SelfMask<pcl::PointXYZ>(tf_listener_, links));
00137 }
00138 }
00139
00140 #include <pluginlib/class_list_macros.h>
00141 PLUGINLIB_EXPORT_CLASS (jsk_perception::RobotToMaskImage, nodelet::Nodelet);