36 #include <jsk_recognition_msgs/Int32Stamped.h>
37 #include <jsk_interactive_marker/IndexRequest.h>
38 #include <jsk_recognition_msgs/PolygonArray.h>
40 #include <boost/algorithm/string.hpp>
42 #include <jsk_topic_tools/log_utils.h>
44 std::shared_ptr<interactive_markers::InteractiveMarkerServer>
server;
53 jsk_recognition_msgs::PolygonArray array_msg;
60 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
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());
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;
96 ss <<
"polygon" <<
"_" << i;
97 int_marker.name = ss.str();
99 visualization_msgs::InteractiveMarkerControl control;
100 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
103 std::stringstream ss;
105 ss << polygon.header.stamp.sec <<
" " << polygon.header.stamp.nsec <<
" " << i;
106 control.name = ss.str();
108 visualization_msgs::Marker
marker;
109 marker.type = visualization_msgs::Marker::TRIANGLE_LIST;
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;
132 control.markers.push_back(
marker);
133 control.always_visible =
true;
134 int_marker.controls.push_back(control);
135 server->insert(int_marker);
141 int main(
int argc,
char** argv)
146 pub = pnh.
advertise<jsk_recognition_msgs::Int32Stamped>(
"selected_index", 1);