bounding_box_marker.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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/BoundingBoxArray.h>
39 #include <ros/ros.h>
40 #include <boost/algorithm/string.hpp>
41 
42 
43 std::shared_ptr<interactive_markers::InteractiveMarkerServer> server;
46 jsk_recognition_msgs::BoundingBoxArray::ConstPtr box_msg;
47 
48 void publishClickedBox(jsk_recognition_msgs::Int32Stamped& msg)
49 {
50  pub.publish(msg);
51  box_pub.publish(box_msg->boxes[msg.data]);
52  jsk_recognition_msgs::BoundingBoxArray array_msg;
53  array_msg.header = box_msg->header;
54  array_msg.boxes.push_back(box_msg->boxes[msg.data]);
55  box_arr_pub.publish(array_msg);
56 }
57 
58 void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
59 {
60  // control_name is "sec nsec index"
61  if (feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN) {
62  std::string control_name = feedback->control_name;
63  ROS_INFO_STREAM("control_name: " << control_name);
64  std::list<std::string> splitted_string;
65  boost::split(splitted_string, control_name, boost::is_space());
66  jsk_recognition_msgs::Int32Stamped index;
67  index.header.stamp.sec = boost::lexical_cast<int>(splitted_string.front());
68  splitted_string.pop_front();
69  index.header.stamp.nsec = boost::lexical_cast<int>(splitted_string.front());
70  splitted_string.pop_front();
71  index.data = boost::lexical_cast<int>(splitted_string.front());
72  publishClickedBox(index);
73  }
74 }
75 
76 bool indexRequest(jsk_interactive_marker::IndexRequest::Request &req,
77  jsk_interactive_marker::IndexRequest::Response &res)
78 {
79  publishClickedBox(req.index);
80 }
81 
82 void boxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
83 {
84  box_msg = msg;
85  server->clear();
86  // create cube markers
87  for (size_t i = 0; i < msg->boxes.size(); i++) {
88  jsk_recognition_msgs::BoundingBox box = msg->boxes[i];
89  visualization_msgs::InteractiveMarker int_marker;
90  int_marker.header.frame_id = box.header.frame_id;
91  int_marker.pose = box.pose;
92  {
93  std::stringstream ss;
94  ss << "box" << "_" << i;
95  int_marker.name = ss.str();
96  }
97  visualization_msgs::InteractiveMarkerControl control;
98  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
99 
100  {
101  std::stringstream ss;
102  // encode several informations into control name
103  ss << box.header.stamp.sec << " " << box.header.stamp.nsec << " " << i;
104  control.name = ss.str();
105  }
106  visualization_msgs::Marker marker;
107  marker.type = visualization_msgs::Marker::CUBE;
108  marker.scale.x = box.dimensions.x + 0.01;
109  marker.scale.y = box.dimensions.y + 0.01;
110  marker.scale.z = box.dimensions.z + 0.01;
111  marker.color.r = 1.0;
112  marker.color.g = 1.0;
113  marker.color.b = 1.0;
114  marker.color.a = 0.0;
115  control.markers.push_back(marker);
116  control.always_visible = true;
117  int_marker.controls.push_back(control);
118  server->insert(int_marker);
119  server->setCallback(int_marker.name, &processFeedback);
120  }
121  server->applyChanges();
122 }
123 
124 int main(int argc, char** argv)
125 {
126  ros::init(argc, argv, "bounding_box_interactive_marker");
127  ros::NodeHandle n, pnh("~");
128  server.reset(new interactive_markers::InteractiveMarkerServer("bounding_box_interactive_marker", "", false));
129  pub = pnh.advertise<jsk_recognition_msgs::Int32Stamped>("selected_index", 1);
130  box_pub = pnh.advertise<jsk_recognition_msgs::BoundingBox>("selected_box", 1);
131  box_arr_pub = pnh.advertise<jsk_recognition_msgs::BoundingBoxArray>("selected_box_array", 1);
132  ros::Subscriber sub = pnh.subscribe("bounding_box_array", 1, boxCallback);
133  ros::spin();
134  server.reset();
135  return 0;
136 }
jsk_recognition_msgs::BoundingBoxArray::ConstPtr box_msg
bool indexRequest(jsk_interactive_marker::IndexRequest::Request &req, jsk_interactive_marker::IndexRequest::Response &res)
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())
void boxCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &msg)
GLfloat n[6][3]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publishClickedBox(jsk_recognition_msgs::Int32Stamped &msg)
ROSCPP_DECL void spin(Spinner &spinner)
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sub
#define ROS_INFO_STREAM(args)
char * index(char *sp, char c)
int main(int argc, char **argv)
ros::Publisher box_pub
ros::Publisher box_arr_pub
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server
ros::Publisher pub
boost::mutex mutex


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