polygon_marker.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Ryohei Ueda and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 #include <jsk_recognition_msgs/Int32Stamped.h>
37 #include <jsk_interactive_marker/IndexRequest.h>
38 #include <jsk_recognition_msgs/PolygonArray.h>
39 #include <ros/ros.h>
40 #include <boost/algorithm/string.hpp>
43 
44 std::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
47 jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg;
48 
49 void publishClickedPolygon(jsk_recognition_msgs::Int32Stamped& msg)
50 {
51  pub.publish(msg);
52  polygon_pub.publish(polygon_msg->polygons[msg.data]);
53  jsk_recognition_msgs::PolygonArray array_msg;
54  array_msg.header = polygon_msg->header;
55  array_msg.polygons.push_back(polygon_msg->polygons[msg.data]);
56  polygon_arr_pub.publish(array_msg);
57 }
58 
60  const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
61 {
62  // control_name is "sec nsec index"
63  if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN) {
64  std::string control_name = feedback->control_name;
65  ROS_INFO("control_name: %s", control_name.c_str());
66  std::list<std::string> splitted_string;
67  boost::split(splitted_string, control_name, boost::is_space());
68  jsk_recognition_msgs::Int32Stamped index;
69  index.header.stamp.sec = boost::lexical_cast<int>(splitted_string.front());
70  splitted_string.pop_front();
71  index.header.stamp.nsec = boost::lexical_cast<int>(splitted_string.front());
72  splitted_string.pop_front();
73  index.data = boost::lexical_cast<int>(splitted_string.front());
74  publishClickedPolygon(index);
75  }
76 }
77 
78 // bool indexRequest(jsk_interactive_marker::IndexRequest::Request &req,
79 // jsk_interactive_marker::IndexRequest::Response &res)
80 // {
81 // publishClickedBox(req.index);
82 // }
83 
84 void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
85 {
86  polygon_msg = msg;
87  server->clear();
88  // create cube markers
89  for (size_t i = 0; i < msg->polygons.size(); i++) {
90  geometry_msgs::PolygonStamped polygon = msg->polygons[i];
91  visualization_msgs::InteractiveMarker int_marker;
92  int_marker.header.frame_id = polygon.header.frame_id;
93  int_marker.pose.orientation.w = 1;
94  {
95  std::stringstream ss;
96  ss << "polygon" << "_" << i;
97  int_marker.name = ss.str();
98  }
99  visualization_msgs::InteractiveMarkerControl control;
100  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
101 
102  {
103  std::stringstream ss;
104  // encode several informations into control name
105  ss << polygon.header.stamp.sec << " " << polygon.header.stamp.nsec << " " << i;
106  control.name = ss.str();
107  }
108  visualization_msgs::Marker marker;
109  marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
110  marker.scale.x = 1.0;
111  marker.scale.y = 1.0;
112  marker.scale.z = 1.0;
113  marker.color.r = 1.0;
114  marker.color.g = 1.0;
115  marker.color.b = 1.0;
116  marker.color.a = 0.0;
119  std::vector<jsk_recognition_utils::Polygon::Ptr> decomposed_triangles
120  = polygon_obj->decomposeToTriangles();
121  for (size_t j = 0; j < decomposed_triangles.size(); j++) {
123  = decomposed_triangles[j]->getVertices();
124  for (size_t k = 0; k < vs.size(); k++) {
125  geometry_msgs::Point p;
126  p.x = vs[k][0];
127  p.y = vs[k][1];
128  p.z = vs[k][2];
129  marker.points.push_back(p);
130  }
131  }
132  control.markers.push_back(marker);
133  control.always_visible = true;
134  int_marker.controls.push_back(control);
135  server->insert(int_marker);
136  server->setCallback(int_marker.name, &processFeedback);
137  }
138  server->applyChanges();
139 }
140 
141 int main(int argc, char** argv)
142 {
143  ros::init(argc, argv, "polygon_interactive_marker");
144  ros::NodeHandle n, pnh("~");
145  server.reset(new interactive_markers::InteractiveMarkerServer("polygon_interactive_marker", "", false));
146  pub = pnh.advertise<jsk_recognition_msgs::Int32Stamped>("selected_index", 1);
147  polygon_pub = pnh.advertise<geometry_msgs::PolygonStamped>("selected_polygon", 1);
148  polygon_arr_pub = pnh.advertise<jsk_recognition_msgs::PolygonArray>("selected_polygon_array", 1);
149  ros::Subscriber sub = pnh.subscribe("polygon_array", 1, polygonCallback);
150  ros::spin();
151  server.reset();
152  return 0;
153 }
void publishClickedPolygon(jsk_recognition_msgs::Int32Stamped &msg)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
GLfloat n[6][3]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher polygon_pub
void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ros::Publisher polygon_arr_pub
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server
#define ROS_INFO(...)
jsk_recognition_msgs::PolygonArray::ConstPtr polygon_msg
boost::mutex mutex
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sub
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
char * index(char *sp, char c)
p
ros::Publisher pub
int main(int argc, char **argv)


jsk_interactive_marker
Author(s): furuta
autogenerated on Sat Mar 20 2021 03:03:33