robot_to_mask_image.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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           // project to 3d
00074           cv::Point uv(u, v);
00075           cv::Point3d p = model.projectPixelTo3dRay(uv);
00076           // check intersection with robot
00077           // ROS_INFO_STREAM("uv( " << u << " , " << v << " )  intersection: " << self_mask_->getMaskIntersection(p.x * max_robot_dist_, p.y * max_robot_dist_, p.z * max_robot_dist_));
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     // genearte urdf model
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);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07