interactive_point_cloud.cpp
Go to the documentation of this file.
1 #include <visualization_msgs/InteractiveMarker.h>
2 #include <visualization_msgs/InteractiveMarkerFeedback.h>
3 #include <geometry_msgs/PoseStamped.h>
4 #include <std_msgs/String.h>
5 #include <tf/tf.h>
6 
10 #include <pcl_ros/transforms.h>
11 #include <tf/transform_listener.h>
13 
14 #include <boost/range/algorithm_ext/erase.hpp>
15 
16 using namespace visualization_msgs;
17 using namespace interactive_markers;
18 using namespace im_helpers;
19 
21  std::string topic_name, std::string server_name ):
22  marker_name_(marker_name)
23  , nh_()
24  , pnh_("~")
25  , tfl_(nh_)
26  , marker_server_(topic_name, server_name, false)
27 {
28 
29  pnh_.param<double>("point_size", point_size_, 0.004);
30  pnh_.param<std::string>("input", input_pointcloud_, "/selected_pointcloud");
31  // pnh_.param<bool>("use_bounding_box", use_bounding_box_, "false");
32  pnh_.param<bool>("use_bounding_box", use_bounding_box_, "true");
33  pnh_.param<std::string>("input_bounding_box", input_bounding_box_, "/bounding_box_marker/selected_box_array");
34  pnh_.param<std::string>("handle_pose", initial_handle_pose_, "/handle_estimator/output_best");
35  pnh_.param<bool>("display_interactive_manipulator", display_interactive_manipulator_, true);
36  //publish
37  pub_click_point_ = pnh_.advertise<geometry_msgs::PointStamped>("right_click_point", 1);
38  pub_left_click_ = pnh_.advertise<geometry_msgs::PointStamped>("left_click_point", 1);
39  pub_left_click_relative_ = pnh_.advertise<geometry_msgs::PointStamped>("left_click_point_relative", 1);
40  pub_marker_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("marker_pose", 1);
41  pub_grasp_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("grasp_pose", 1);
42  pub_box_movement_ = pnh_.advertise<jsk_recognition_msgs::BoundingBoxMovement>("box_movement", 1);
43  pub_handle_pose_ = pnh_.advertise<geometry_msgs::PoseStamped>("handle_pose", 1);
44  pub_handle_pose_array_ = pnh_.advertise<geometry_msgs::PoseArray>("handle_pose_array", 1);
45 
46  //subscribe
47  sub_handle_pose_ = pnh_.subscribe<geometry_msgs::PoseStamped> ("set_handle_pose", 1, boost::bind( &InteractivePointCloud::setHandlePoseCallback, this, _1));
48  sub_marker_pose_ = pnh_.subscribe<geometry_msgs::PoseStamped>("set_marker_pose", 1, boost::bind( &InteractivePointCloud::setMarkerPoseCallback, this, _1));
49  sub_point_cloud_.subscribe(pnh_, input_pointcloud_, 1);
50 
51 
52  if(use_bounding_box_){
53  //point cloud and bounding box
54  sync_ = std::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
55  sub_bounding_box_.subscribe(pnh_,input_bounding_box_, 1);
56  sub_initial_handle_pose_.subscribe(pnh_, initial_handle_pose_, 1);
58  sync_->registerCallback(boost::bind(&InteractivePointCloud::pointCloudAndBoundingBoxCallback, this, _1, _2, _3));
59 
60  }else{
62  }
63  srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh_);
64  dynamic_reconfigure::Server<Config>::CallbackType f =
65  boost::bind (&InteractivePointCloud::configCallback, this, _1, _2);
66  srv_->setCallback (f);
67 
68  makeMenu();
69 }
70 
72 
73 void InteractivePointCloud::configCallback(Config &config, uint32_t level)
74 {
75  point_size_ = config.point_size;
76  if(display_interactive_manipulator_ != config.display_interactive_manipulator){
77  display_interactive_manipulator_ = config.display_interactive_manipulator;
78  visualization_msgs::InteractiveMarker int_marker;
79  marker_server_.get(marker_name_, int_marker );
81  addVisible6DofControl(int_marker);
82  }else{
83  for(std::vector<visualization_msgs::InteractiveMarkerControl>::iterator it=int_marker.controls.begin(); it!=int_marker.controls.end();){
84  if(it->interaction_mode==visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS
85  || it->interaction_mode==visualization_msgs::InteractiveMarkerControl::MOVE_AXIS){
86  it = int_marker.controls.erase(it);
87  }else{
88  it++;
89  }
90  }
91  }
93  marker_server_.insert(int_marker);
95  }
96 }
97 
98 void InteractivePointCloud::pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud){
99  makeMarker(cloud, point_size_ );
100 }
101 
102 void InteractivePointCloud::pointCloudAndBoundingBoxCallback(const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle){
103  makeMarker(cloud, box, handle, point_size_ );
104 }
105 
106 
107 
108 void InteractivePointCloud::setHandlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps){
109  if( ps->header.stamp == current_box_.header.stamp ){
110  if(current_box_.boxes.size() > 0){
111  handle_pose_ = *ps;
112 
113  tf::Transform tf_ps, tf_box;
114  tf_ps.setOrigin(tf::Vector3(ps->pose.position.x, ps->pose.position.y, ps->pose.position.z));
115  tf_ps.setRotation(tf::Quaternion( ps->pose.orientation.x, ps->pose.orientation.y, ps->pose.orientation.z, ps->pose.orientation.w));
116 
117  geometry_msgs::Pose pose = current_box_.boxes[0].pose;
118  tf_box.setOrigin(tf::Vector3(pose.position.x, pose.position.y, pose.position.z));
119  tf_box.setRotation(tf::Quaternion( pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w));
120 
121  handle_tf_ = tf_box.inverseTimes(tf_ps);
122  exist_handle_tf_ = true;
124 
125  /* set box_movement_ */
126  geometry_msgs::Pose handle_pose;
127  handle_pose.position.x = handle_tf_.getOrigin().x();
128  handle_pose.position.y = handle_tf_.getOrigin().y();
129  handle_pose.position.z = handle_tf_.getOrigin().z();
130  handle_pose.orientation.x = handle_tf_.getRotation().x();
131  handle_pose.orientation.y = handle_tf_.getRotation().y();
132  handle_pose.orientation.z = handle_tf_.getRotation().z();
133  handle_pose.orientation.w = handle_tf_.getRotation().w();
134 
135  box_movement_.handle_pose = handle_pose;
136  }
137  }
138 }
139 
140 void InteractivePointCloud::setMarkerPoseCallback( const geometry_msgs::PoseStampedConstPtr &pose_stamped_msg){
141  marker_server_.setPose(marker_name_, pose_stamped_msg->pose, pose_stamped_msg->header);
143 }
144 
145 // create menu
147 {
148  menu_handler_.insert( "Move", boost::bind( &InteractivePointCloud::move, this, _1) );
149 
150  menu_handler_.insert( "Hide", boost::bind( &InteractivePointCloud::hide, this, _1));
151 }
152 
153 //publish marker pose
154 void InteractivePointCloud::move( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback ){
155  box_movement_.destination = marker_pose_;
157 
158 }
159 
160 void InteractivePointCloud::leftClickPoint( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
161 {
162  if(!feedback->mouse_point_valid)
163  {
164  ROS_WARN("Clicked point had an invalid position. Not looking there!");
165  return;
166  }
167 
168  ROS_DEBUG_STREAM_NAMED("cloud_handler", "Button click in frame "
169  << feedback->header.frame_id << " at point\n" << feedback->mouse_point );
170  geometry_msgs::PointStamped click_point;
171  click_point.point = feedback->mouse_point;
172  click_point.header = feedback->header;
173  click_point.header.stamp = ros::Time::now();
174  pub_left_click_.publish(click_point);
175  tf::Transform transform;
176  tf::poseMsgToTF(feedback->pose, transform);
177  tf::Vector3 vector_absolute(feedback->mouse_point.x, feedback->mouse_point.y, feedback->mouse_point.z);
178  tf::Vector3 vector_relative=transform.inverse() * vector_absolute;
179  click_point.point.x=vector_relative.getX();
180  click_point.point.y=vector_relative.getY();
181  click_point.point.z=vector_relative.getZ();
182  pub_left_click_relative_.publish(click_point);
183 }
184 
185 void InteractivePointCloud::hide( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
186 {
189 }
190 
191 
192 void InteractivePointCloud::markerFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback){
193  marker_pose_.pose = feedback->pose;
194  marker_pose_.header = feedback->header;
195  if(exist_handle_tf_){
197  }
198 }
199 
202 }
203 
204 void InteractivePointCloud::publishHandPose( geometry_msgs::PoseStamped box_pose){
205  tf::Transform tf_marker;
206  tf_marker.setOrigin(tf::Vector3(box_pose.pose.position.x, box_pose.pose.position.y, box_pose.pose.position.z));
207  tf_marker.setRotation(tf::Quaternion( box_pose.pose.orientation.x, box_pose.pose.orientation.y, box_pose.pose.orientation.z, box_pose.pose.orientation.w));
208 
209  tf_marker = tf_marker * handle_tf_;
210  geometry_msgs::PoseStamped handle_pose;
211  handle_pose.header.frame_id = box_pose.header.frame_id;
212  handle_pose.pose.position.x = tf_marker.getOrigin().x();
213  handle_pose.pose.position.y = tf_marker.getOrigin().y();
214  handle_pose.pose.position.z = tf_marker.getOrigin().z();
215  handle_pose.pose.orientation.x = tf_marker.getRotation().x();
216  handle_pose.pose.orientation.y = tf_marker.getRotation().y();
217  handle_pose.pose.orientation.z = tf_marker.getRotation().z();
218  handle_pose.pose.orientation.w = tf_marker.getRotation().w();
219 
220  pub_handle_pose_.publish(handle_pose);
221 
222  geometry_msgs::PoseArray handle_pose_array;
223  handle_pose_array.header = handle_pose.header;
224  handle_pose_array.poses.push_back(handle_pose.pose);
225  pub_handle_pose_array_.publish(handle_pose_array);
226 }
227 
228 void InteractivePointCloud::makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud,float size){
229  makeMarker(cloud, jsk_recognition_msgs::BoundingBoxArray::ConstPtr(), geometry_msgs::PoseStamped::ConstPtr(), size);
230 }
231 void InteractivePointCloud::makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, const geometry_msgs::PoseStampedConstPtr handle, float size)
232 {
233  exist_handle_tf_ = false;
234  if(cloud){
235  current_croud_ = *cloud;
236  }
237  if(box){
238  current_box_ = *box;
239  }
240 
241  InteractiveMarker int_marker;
242  int_marker.name = marker_name_;
243 
244  pcl::PointCloud<PointT> pcl_cloud, transform_cloud;
245  pcl::fromROSMsg(*cloud, pcl_cloud);
246 
247  if(box && box->boxes.size() > 0){
248  jsk_recognition_msgs::BoundingBox first_box = box->boxes[0];
249  int_marker.pose = first_box.pose;
250  int_marker.header.frame_id = first_box.header.frame_id;
251 
252  marker_pose_.header = box->header;
253  marker_pose_.pose = first_box.pose;
254 
255  tf::Transform transform;
256  tf::poseMsgToTF(first_box.pose, transform);
257 
258  pcl_ros::transformPointCloud(pcl_cloud, transform_cloud, transform.inverse());
259  pcl_cloud = transform_cloud;
260 
261  box_movement_.box = first_box;
262  box_movement_.header.frame_id = first_box.header.frame_id;
263 
264  if(handle->header.frame_id != ""){
265  setHandlePoseCallback(handle);
266  }
267  }
268  else{
269  int_marker.pose.position.x=int_marker.pose.position.y=int_marker.pose.position.z=int_marker.pose.orientation.x=int_marker.pose.orientation.y=int_marker.pose.orientation.z=0;
270  int_marker.pose.orientation.w=1;
271  }
272 
273 
274  int num_points = pcl_cloud.points.size();
275 
276  Marker marker;
277  marker.color.r = 1.0;
278  marker.color.g = 1.0;
279  marker.color.b = 1.0;
280  marker.color.a = 1.0;
281  marker.frame_locked = false;
282  if(num_points > 0)
283  {
284 
285  int_marker.header = cloud->header;
286 
287  InteractiveMarkerControl control;
288  control.always_visible = true;
289  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
290  //control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_3D;
291  control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
292 
293  int_marker.header.stamp = ros::Time::now();
294 
295  marker.scale.x = size;
296  marker.scale.y = size;
297  marker.scale.z = size;
298  marker.type = visualization_msgs::Marker::SPHERE_LIST;
299 
300  marker.points.resize( num_points );
301  marker.colors.resize( num_points );
302  //point cloud
303  for ( int i=0; i<num_points; i++)
304  {
305  marker.points[i].x = pcl_cloud.points[i].x;
306  marker.points[i].y = pcl_cloud.points[i].y;
307  marker.points[i].z = pcl_cloud.points[i].z;
308  marker.colors[i].r = pcl_cloud.points[i].r/255.;
309  marker.colors[i].g = pcl_cloud.points[i].g/255.;
310  marker.colors[i].b = pcl_cloud.points[i].b/255.;
311  marker.colors[i].a = 1.0;
312  }
313  control.markers.push_back( marker );
314 
315  //bounding box
316  if(box && box->boxes.size() > 0){
317  Marker bounding_box_marker;
318  bounding_box_marker.color.r = 0.0;
319  bounding_box_marker.color.g = 0.0;
320  bounding_box_marker.color.b = 1.0;
321  bounding_box_marker.color.a = 1.0;
322  bounding_box_marker.type = visualization_msgs::Marker::LINE_LIST;
323  bounding_box_marker.scale.x = 0.01; //line width
324  bounding_box_marker.points.resize(24);
325 
326  double x = box->boxes[0].dimensions.x / 2;
327  double y = box->boxes[0].dimensions.y / 2;
328  double z = box->boxes[0].dimensions.z / 2;
329  for(int i=0; i<4; i++)
330  {
331  if(i%2 == 0){
332  bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = x;
333 
334  }else{
335  bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = - x;
336  }
337  if(i%4 < 2){
338  bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = y;
339 
340  }else{
341  bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = - y;
342 
343  }
344  bounding_box_marker.points[2*i].z = z;
345  bounding_box_marker.points[2*i+1].z = - z;
346  }
347 
348  for(int i=4; i<8; i++)
349  {
350  if(i%2 == 0){
351  bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = x;
352 
353  }else{
354  bounding_box_marker.points[2*i].x = bounding_box_marker.points[2*i+1].x = - x;
355  }
356  if(i%4 < 2){
357  bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = z;
358 
359  }else{
360  bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = - z;
361 
362  }
363  bounding_box_marker.points[2*i].y = y;
364  bounding_box_marker.points[2*i+1].y = - y;
365  }
366 
367  for(int i=8; i<12; i++)
368  {
369  if(i%2 == 0){
370  bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = z;
371 
372  }else{
373  bounding_box_marker.points[2*i].z = bounding_box_marker.points[2*i+1].z = - z;
374  }
375  if(i%4 < 2){
376  bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = y;
377 
378  }else{
379  bounding_box_marker.points[2*i].y = bounding_box_marker.points[2*i+1].y = - y;
380 
381  }
382  bounding_box_marker.points[2*i].x = x;
383  bounding_box_marker.points[2*i+1].x = - x;
384  }
385 
386  control.markers.push_back( bounding_box_marker );
387  }
388  int_marker.controls.push_back( control );
390  addVisible6DofControl(int_marker);
391  }
392  marker_server_.insert( int_marker, boost::bind( &InteractivePointCloud::leftClickPoint, this, _1 ),
393  visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
394  marker_server_.setCallback( int_marker.name,
395  boost::bind( &InteractivePointCloud::markerFeedback, this, _1) );
396 
399  ROS_INFO("made interactive point cloud");
400 
402  }
403 }
f
void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
jsk_interactive_marker::ParentAndChildInteractiveMarkerServer marker_server_
sensor_msgs::PointCloud2 current_croud_
void makeMarker(const sensor_msgs::PointCloud2ConstPtr cloud, float size)
#define ROS_DEBUG_STREAM_NAMED(name, args)
void publish(const boost::shared_ptr< M > &message) const
x
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_bounding_box_
ros::Publisher pub_handle_pose_array_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
geometry_msgs::PoseStamped handle_pose_
void setHandlePoseCallback(const geometry_msgs::PoseStampedConstPtr &ps)
jsk_recognition_msgs::BoundingBoxArray current_box_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
pose
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
#define ROS_WARN(...)
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
void markerFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void addVisible6DofControl(visualization_msgs::InteractiveMarker &msg, bool fixed=false, bool visible=true)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void insert(const visualization_msgs::InteractiveMarker &int_marker)
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_initial_handle_pose_
y
void move(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
TFSIMD_FORCE_INLINE const tfScalar & z() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
geometry_msgs::PoseStamped marker_pose_
std::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Transform inverse() const
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_point_cloud_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INTERACTIVE_MARKERS_PUBLIC bool get(std::string name, visualization_msgs::InteractiveMarker &int_marker) const
void setMarkerPoseCallback(const geometry_msgs::PoseStampedConstPtr &pose_stamped_msg)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
virtual void configCallback(Config &config, uint32_t level)
void pointCloudAndBoundingBoxCallback(const sensor_msgs::PointCloud2ConstPtr &cloud, const jsk_recognition_msgs::BoundingBoxArrayConstPtr &box, const geometry_msgs::PoseStampedConstPtr &handle)
std::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
jsk_recognition_msgs::BoundingBoxMovement box_movement_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void hide(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Clear the cloud stored in this object.
Quaternion getRotation() const
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void leftClickPoint(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
ros::Publisher pub_left_click_relative_
INTERACTIVE_MARKERS_PUBLIC bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
void publishHandPose(geometry_msgs::PoseStamped box_pose)
Transform inverseTimes(const Transform &t) const
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
jsk_interactive_marker::InteractivePointCloudConfig Config
z
InteractivePointCloud(std::string marker_name, std::string topic_name, std::string server_name)
interactive_markers::MenuHandler menu_handler_
Connection registerCallback(const C &callback)


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