1 #include <visualization_msgs/InteractiveMarker.h> 
    2 #include <visualization_msgs/InteractiveMarkerFeedback.h> 
    3 #include <geometry_msgs/PoseStamped.h> 
    4 #include <std_msgs/String.h> 
   14 #include <boost/range/algorithm_ext/erase.hpp> 
   16 using namespace visualization_msgs;
 
   21                            std::string topic_name, std::string server_name ):
 
   22   marker_name_(marker_name)
 
   26   , marker_server_(topic_name, server_name, false)
 
   54     sync_ = std::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
 
   63   srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (
pnh_);
 
   64   dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   66   srv_->setCallback (
f);
 
   78     visualization_msgs::InteractiveMarker int_marker;
 
   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);
 
  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));
 
  126       geometry_msgs::Pose handle_pose;
 
  162   if(!feedback->mouse_point_valid)
 
  164     ROS_WARN(
"Clicked point had an invalid position. Not looking there!");
 
  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;
 
  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();
 
  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));
 
  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();
 
  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);
 
  229   makeMarker(cloud, jsk_recognition_msgs::BoundingBoxArray::ConstPtr(), geometry_msgs::PoseStamped::ConstPtr(), 
size);
 
  231 void InteractivePointCloud::makeMarker(
const sensor_msgs::PointCloud2ConstPtr cloud, 
const jsk_recognition_msgs::BoundingBoxArrayConstPtr box, 
const geometry_msgs::PoseStampedConstPtr handle, 
float size)
 
  241   InteractiveMarker int_marker;
 
  244   pcl::PointCloud<PointT> pcl_cloud, transform_cloud;
 
  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;
 
  259     pcl_cloud = transform_cloud;
 
  264     if(handle->header.frame_id != 
""){
 
  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;
 
  274   int num_points = pcl_cloud.points.size();
 
  281   marker.frame_locked = 
false;
 
  285       int_marker.header = cloud->header;
 
  287       InteractiveMarkerControl control;
 
  288       control.always_visible = 
true;
 
  289       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
 
  291       control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
 
  298       marker.type = visualization_msgs::Marker::SPHERE_LIST;
 
  300       marker.points.resize( num_points );
 
  301       marker.colors.resize( num_points );
 
  303       for ( 
int i=0; 
i<num_points; 
i++)
 
  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.;
 
  313       control.markers.push_back( 
marker );
 
  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; 
 
  324         bounding_box_marker.points.resize(24);
 
  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++)
 
  332               bounding_box_marker.points[2*
i].x = bounding_box_marker.points[2*
i+1].x = 
x;
 
  335               bounding_box_marker.points[2*
i].x = bounding_box_marker.points[2*
i+1].x = - 
x;
 
  338               bounding_box_marker.points[2*
i].y = bounding_box_marker.points[2*
i+1].y = 
y;
 
  341               bounding_box_marker.points[2*
i].y = bounding_box_marker.points[2*
i+1].y = - 
y;
 
  344             bounding_box_marker.points[2*
i].z = 
z;
 
  345             bounding_box_marker.points[2*
i+1].z = - 
z;
 
  348         for(
int i=4; 
i<8; 
i++)
 
  351               bounding_box_marker.points[2*
i].x = bounding_box_marker.points[2*
i+1].x = 
x;
 
  354               bounding_box_marker.points[2*
i].x = bounding_box_marker.points[2*
i+1].x = - 
x;
 
  357               bounding_box_marker.points[2*
i].z = bounding_box_marker.points[2*
i+1].z = 
z;
 
  360               bounding_box_marker.points[2*
i].z = bounding_box_marker.points[2*
i+1].z = - 
z;
 
  363             bounding_box_marker.points[2*
i].y = 
y;
 
  364             bounding_box_marker.points[2*
i+1].y = - 
y;
 
  367         for(
int i=8; 
i<12; 
i++)
 
  370               bounding_box_marker.points[2*
i].z = bounding_box_marker.points[2*
i+1].z = 
z;
 
  373               bounding_box_marker.points[2*
i].z = bounding_box_marker.points[2*
i+1].z = - 
z;
 
  376               bounding_box_marker.points[2*
i].y = bounding_box_marker.points[2*
i+1].y = 
y;
 
  379               bounding_box_marker.points[2*
i].y = bounding_box_marker.points[2*
i+1].y = - 
y;
 
  382             bounding_box_marker.points[2*
i].x = 
x;
 
  383             bounding_box_marker.points[2*
i+1].x = - 
x;
 
  386         control.markers.push_back( bounding_box_marker );
 
  388       int_marker.controls.push_back( control );
 
  393                              visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK);
 
  399       ROS_INFO(
"made interactive point cloud");