polygon_marker.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Ryohei Ueda and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <interactive_markers/interactive_marker_server.h>
00036 #include <jsk_recognition_msgs/Int32Stamped.h>
00037 #include <jsk_interactive_marker/IndexRequest.h>
00038 #include <jsk_recognition_msgs/PolygonArray.h>
00039 #include <ros/ros.h>
00040 #include <boost/algorithm/string.hpp>
00041 #include <jsk_recognition_utils/geo/polygon.h>
00042 #include <jsk_topic_tools/log_utils.h>
00043 
00044 std::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
00045 boost::mutex mutex;
00046 ros::Publisher pub, polygon_pub, polygon_arr_pub;
00047 jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg;
00048 
00049 void publishClickedPolygon(jsk_recognition_msgs::Int32Stamped& msg)
00050 {
00051   pub.publish(msg);
00052   polygon_pub.publish(polygon_msg->polygons[msg.data]);
00053   jsk_recognition_msgs::PolygonArray array_msg;
00054   array_msg.header = polygon_msg->header;
00055   array_msg.polygons.push_back(polygon_msg->polygons[msg.data]);
00056   polygon_arr_pub.publish(array_msg);
00057 }
00058 
00059 void processFeedback(
00060   const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
00061 {
00062   boost::mutex::scoped_lock(mutex);
00063   // control_name is "sec nsec index"
00064   if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN) {
00065     std::string control_name = feedback->control_name;
00066     ROS_INFO("control_name: %s", control_name.c_str());
00067     std::list<std::string> splitted_string;
00068     boost::split(splitted_string, control_name, boost::is_space());
00069     jsk_recognition_msgs::Int32Stamped index;
00070     index.header.stamp.sec = boost::lexical_cast<int>(splitted_string.front());
00071     splitted_string.pop_front();
00072     index.header.stamp.nsec = boost::lexical_cast<int>(splitted_string.front());
00073     splitted_string.pop_front();
00074     index.data = boost::lexical_cast<int>(splitted_string.front());
00075     publishClickedPolygon(index);
00076   }
00077 }
00078 
00079 // bool indexRequest(jsk_interactive_marker::IndexRequest::Request  &req,
00080 //                   jsk_interactive_marker::IndexRequest::Response &res)
00081 // {
00082 //   publishClickedBox(req.index);
00083 // }
00084 
00085 void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00086 {
00087   boost::mutex::scoped_lock(mutex);
00088   polygon_msg = msg;
00089   server->clear();
00090   // create cube markers
00091   for (size_t i = 0; i < msg->polygons.size(); i++) {
00092     geometry_msgs::PolygonStamped polygon = msg->polygons[i];
00093     visualization_msgs::InteractiveMarker int_marker;
00094     int_marker.header.frame_id = polygon.header.frame_id;
00095     int_marker.pose.orientation.w = 1;
00096     {
00097       std::stringstream ss;
00098       ss << "polygon" << "_" << i;
00099       int_marker.name = ss.str();
00100     }
00101     visualization_msgs::InteractiveMarkerControl control;
00102     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00103     
00104     {
00105       std::stringstream ss;
00106       // encode several informations into control name
00107       ss << polygon.header.stamp.sec << " " << polygon.header.stamp.nsec << " " << i;
00108       control.name = ss.str();
00109     }
00110     visualization_msgs::Marker marker;
00111     marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
00112     marker.scale.x = 1.0;
00113     marker.scale.y = 1.0;
00114     marker.scale.z = 1.0;
00115     marker.color.r = 1.0;
00116     marker.color.g = 1.0;
00117     marker.color.b = 1.0;
00118     marker.color.a = 0.0;
00119     jsk_recognition_utils::Polygon::Ptr polygon_obj
00120       = jsk_recognition_utils::Polygon::fromROSMsgPtr(polygon.polygon);
00121     std::vector<jsk_recognition_utils::Polygon::Ptr> decomposed_triangles
00122       = polygon_obj->decomposeToTriangles();
00123     for (size_t j = 0; j < decomposed_triangles.size(); j++) {
00124       jsk_recognition_utils::Vertices vs
00125         = decomposed_triangles[j]->getVertices();
00126       for (size_t k = 0; k < vs.size(); k++) {
00127         geometry_msgs::Point p;
00128         p.x = vs[k][0];
00129         p.y = vs[k][1];
00130         p.z = vs[k][2];
00131         marker.points.push_back(p);
00132       }
00133     }
00134     control.markers.push_back(marker);
00135     control.always_visible = true;
00136     int_marker.controls.push_back(control);
00137     server->insert(int_marker);
00138     server->setCallback(int_marker.name, &processFeedback);
00139   }
00140   server->applyChanges();
00141 }
00142 
00143 int main(int argc, char** argv)
00144 {
00145   ros::init(argc, argv, "polygon_interactive_marker");
00146   ros::NodeHandle n, pnh("~");
00147   server.reset(new interactive_markers::InteractiveMarkerServer("polygon_interactive_marker", "", false));
00148   pub = pnh.advertise<jsk_recognition_msgs::Int32Stamped>("selected_index", 1);
00149   polygon_pub = pnh.advertise<geometry_msgs::PolygonStamped>("selected_polygon", 1);
00150   polygon_arr_pub = pnh.advertise<jsk_recognition_msgs::PolygonArray>("selected_polygon_array", 1);
00151   ros::Subscriber sub = pnh.subscribe("polygon_array", 1, polygonCallback);
00152   ros::spin();
00153   server.reset();
00154   return 0;
00155 }


jsk_interactive_marker
Author(s): furuta
autogenerated on Wed May 1 2019 02:40:31