34 #include <rc_pick_client/SetRegionOfInterest.h> 
   35 #include <rc_pick_client/GetRegionsOfInterest.h> 
   41   nh_ = std::make_shared<ros::NodeHandle>();
 
   48   ROS_INFO(
"Disconnecting the interactive region of interest server..");
 
   54   tf::Vector3 u(q.x(), q.y(), q.z());
 
   56   rot_v = 2.0f * u.
dot(v) * u + (w * w - u.dot(u)) * v + 2.0
f * w * u.cross(v);
 
   60     const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
 
   62   ROS_DEBUG_STREAM(feedback->marker_name << 
" is now at " << feedback->pose.position.x << 
", " 
   63                                          << feedback->pose.position.y << 
", " << feedback->pose.position.z);
 
   65   visualization_msgs::InteractiveMarker corner_int_marker;
 
   66   server_->get(
"corner_0", corner_int_marker);
 
   68   geometry_msgs::Pose corner_pose;
 
   70   if (corner_int_marker.pose.orientation.w == 0)
 
   71     corner_int_marker.pose.orientation.w = 1;
 
   74   double orientation_change = (feedback->pose.orientation.x + feedback->pose.orientation.y +
 
   75                                feedback->pose.orientation.z + feedback->pose.orientation.w) -
 
   76                               (corner_int_marker.pose.orientation.x + corner_int_marker.pose.orientation.y +
 
   77                                corner_int_marker.pose.orientation.z + corner_int_marker.pose.orientation.w);
 
   78   if (orientation_change < 0)
 
   79     orientation_change *= -1;
 
   80   bool center_has_rotated = (orientation_change > 0.001);
 
   82   corner_pose.orientation = feedback->pose.orientation;
 
   84   if (center_has_rotated)
 
   93     tf::Vector3 transf_position;
 
   94     tf::Vector3 translation_corner_to_center(corner_int_marker.pose.position.x - feedback->pose.position.x,
 
   95                                              corner_int_marker.pose.position.y - feedback->pose.position.y,
 
   96                                              corner_int_marker.pose.position.z - feedback->pose.position.z);
 
   98     corner_pose.position.x = transf_position.x() + feedback->pose.position.x;
 
   99     corner_pose.position.y = transf_position.y() + feedback->pose.position.y;
 
  100     corner_pose.position.z = transf_position.z() + feedback->pose.position.z;
 
  102     ROS_DEBUG_STREAM(
"center quaternion: " << q_center.x() << 
"," << q_center.y() << 
"," << q_center.z() << 
"," 
  104     ROS_DEBUG_STREAM(
"corner quaternion: " << q_corner.x() << 
"," << q_corner.y() << 
"," << q_corner.z() << 
"," 
  106     ROS_DEBUG_STREAM(
"rotation quaternion: " << rot_quaternion.x() << 
"," << rot_quaternion.y() << 
"," 
  107                                              << rot_quaternion.z() << 
"," << rot_quaternion.w());
 
  112     corner_pose.position.x = corner_int_marker.pose.position.x + feedback->pose.position.x - 
center_position_.x();
 
  113     corner_pose.position.y = corner_int_marker.pose.position.y + feedback->pose.position.y - 
center_position_.y();
 
  114     corner_pose.position.z = corner_int_marker.pose.position.z + feedback->pose.position.z - 
center_position_.z();
 
  116   server_->setPose(
"corner_0", corner_pose);
 
  124                    << 
" is now at " << corner_pose.position.x << 
", " << corner_pose.position.y << 
", " 
  125                    << corner_pose.position.z);
 
  129     const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
 
  131   tf::Vector3 position;
 
  146     const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
 
  148   ROS_DEBUG_STREAM(feedback->marker_name << 
" is now at " << feedback->pose.position.x << 
", " 
  149                                          << feedback->pose.position.y << 
", " << feedback->pose.position.z);
 
  150   tf::Vector3 present_dimensions(feedback->pose.position.x - 
center_position_.x(),
 
  164   visualization_msgs::Marker marker;
 
  170     float center_scale = 2;
 
  171     marker.scale.x = center_scale * box_dimensions.x();
 
  172     marker.scale.y = center_scale * box_dimensions.y();
 
  173     marker.scale.z = center_scale * box_dimensions.z();
 
  174     marker.color.r = 150 / 255.0;
 
  175     marker.color.g = 104 / 2;
 
  176     marker.color.b = 251 / 255.0;
 
  177     marker.color.a = 0.3;
 
  181     marker.scale.x = box_dimensions.x();
 
  182     marker.scale.y = box_dimensions.y();
 
  183     marker.scale.z = box_dimensions.z();
 
  184     marker.color.r = 255 / 255.0;
 
  185     marker.color.g = 204 / 2;
 
  186     marker.color.b = 0 / 255.0;
 
  187     marker.color.a = 1.0;
 
  199     visualization_msgs::InteractiveMarkerControl control;
 
  200     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  201     control.orientation.w = 1;
 
  202     control.orientation.x = 1;
 
  203     control.orientation.y = 0;
 
  204     control.orientation.z = 0;
 
  205     control.name = 
"move_x";
 
  206     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  207     interactive_marker.controls.push_back(control);
 
  209     control.name = 
"move_y";
 
  210     control.orientation.w = 1;
 
  211     control.orientation.x = 0;
 
  212     control.orientation.y = 1;
 
  213     control.orientation.z = 0;
 
  214     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  215     interactive_marker.controls.push_back(control);
 
  217     control.name = 
"move_z";
 
  218     control.orientation.w = 1;
 
  219     control.orientation.x = 0;
 
  220     control.orientation.y = 0;
 
  221     control.orientation.z = 1;
 
  222     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  223     interactive_marker.controls.push_back(control);
 
  228     visualization_msgs::InteractiveMarkerControl control;
 
  229     control.orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED;
 
  230     control.orientation.w = 0.923879468105164;
 
  231     control.orientation.x = 0;
 
  232     control.orientation.y = 0.382683587855188;
 
  233     control.orientation.z = 0;
 
  234     control.name = 
"move_x";
 
  235     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  236     interactive_marker.controls.push_back(control);
 
  245   visualization_msgs::InteractiveMarkerControl control;
 
  246   control.orientation_mode = visualization_msgs::InteractiveMarkerControl::INHERIT;
 
  247   control.orientation.w = 1;
 
  248   control.orientation.x = 1;
 
  249   control.orientation.y = 0;
 
  250   control.orientation.z = 0;
 
  251   control.name = 
"move_x";
 
  252   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  253   interactive_marker.controls.push_back(control);
 
  256     control.name = 
"rotate_x";
 
  257     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  258     interactive_marker.controls.push_back(control);
 
  261   control.name = 
"move_y";
 
  262   control.orientation.w = 1;
 
  263   control.orientation.x = 0;
 
  264   control.orientation.y = 1;
 
  265   control.orientation.z = 0;
 
  266   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  267   interactive_marker.controls.push_back(control);
 
  270     control.name = 
"rotate_y";
 
  271     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  272     interactive_marker.controls.push_back(control);
 
  275   control.name = 
"move_z";
 
  276   control.orientation.w = 1;
 
  277   control.orientation.x = 0;
 
  278   control.orientation.y = 0;
 
  279   control.orientation.z = 1;
 
  280   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
  281   interactive_marker.controls.push_back(control);
 
  285     control.name = 
"rotate_z";
 
  286     control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
  287     interactive_marker.controls.push_back(control);
 
  293                                                     const tf::Vector3& position, 
bool is_center,
 
  296   visualization_msgs::InteractiveMarker int_marker;
 
  300   int_marker.scale = 1.7 * box_dimensions[box_dimensions.maxAxis()];
 
  302   int_marker.name = int_marker_name;
 
  303   int_marker.description = int_marker_description;
 
  306   visualization_msgs::InteractiveMarkerControl control;
 
  307   control.always_visible = is_center;
 
  308   control.markers.push_back(
makeMarker(box_dimensions, is_center));
 
  309   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::NONE;
 
  310   int_marker.controls.push_back(control);
 
  311   int_marker.controls.back();
 
  313   if (
interactive_roi_.primitive.type == shape_msgs::SolidPrimitive::Type::BOX)
 
  326   else if (
interactive_roi_.primitive.type == shape_msgs::SolidPrimitive::Type::SPHERE)
 
  341     ROS_FATAL(
"The provided shape is currently not supported.");
 
  350   tf::Vector3 corner_position_rot;
 
  351   if (
interactive_roi_.primitive.type == shape_msgs::SolidPrimitive::Type::BOX)
 
  360   else if (
interactive_roi_.primitive.type == shape_msgs::SolidPrimitive::Type::SPHERE)
 
  366     corner_position_rot = tf::Vector3(
dimensions_.x(), 0, 0);
 
  368                           corner_position_rot);
 
  386   if (
interactive_roi_.primitive.type == shape_msgs::SolidPrimitive::Type::BOX)