9 inline geometry_msgs::Pose 
inverse(geometry_msgs::Pose pose){
 
   10   Eigen::Affine3d pose_eigen;
 
   18   ROS_INFO(
"Init TransformableObject");
 
   46   visualization_msgs::InteractiveMarkerControl control;
 
   48   std::vector<visualization_msgs::InteractiveMarkerControl> controls;
 
   49   control.orientation_mode = orientation_mode;
 
   50   control.orientation.w = 1;
 
   51   control.orientation.x = 1;
 
   52   control.orientation.y = 0;
 
   53   control.orientation.z = 0;
 
   54   control.name = 
"rotate_x";
 
   55   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
   56   controls.push_back(control);
 
   57   control.name = 
"move_x";
 
   58   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
   59   controls.push_back(control);
 
   61   control.orientation.w = 1;
 
   62   control.orientation.x = 0;
 
   63   control.orientation.y = 1;
 
   64   control.orientation.z = 0;
 
   65   control.name = 
"rotate_z";
 
   66   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
   67   controls.push_back(control);
 
   68   control.name = 
"move_z";
 
   69   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
   70   controls.push_back(control);
 
   72   control.orientation.w = 1;
 
   73   control.orientation.x = 0;
 
   74   control.orientation.y = 0;
 
   75   control.orientation.z = 1;
 
   76   control.name = 
"rotate_y";
 
   77   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
 
   78   controls.push_back(control);
 
   79   control.name = 
"move_y";
 
   80   control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
 
   81   controls.push_back(control);
 
   89   visualization_msgs::InteractiveMarkerControl marker_control;
 
   90   marker_control.always_visible = always_visible;
 
   91   marker_control.markers.push_back(
marker);
 
   92   marker_control.interaction_mode = interaction_mode;
 
   93   int_marker.controls.push_back(marker_control);
 
  100     int_marker.controls.insert(int_marker.controls.end(), rotate_controls.begin(), rotate_controls.end());
 
  105   visualization_msgs::InteractiveMarker int_marker;
 
  110   int_marker.name = 
name_;
 
  114     int_marker.description = 
"";
 
  116   int_marker.pose = 
pose_;
 
  122   if(for_interactive_control) {
 
  126     Eigen::Affine3d control_offset_eigen;
 
  128     Eigen::Affine3d pose_eigen;
 
  135   if(for_interactive_control) {
 
  139     geometry_msgs::Pose 
pose;
 
  140     Eigen::Affine3d control_offset_eigen;
 
  142     Eigen::Affine3d pose_eigen;
 
  152   Eigen::Vector3d original_p(
msg.position.x, 
msg.position.y, 
msg.position.z);
 
  153   Eigen::Quaterniond original_q;
 
  155   Eigen::Quaterniond diff_q;
 
  157   Eigen::Quaterniond updated_q;
 
  159      original_p = Eigen::Affine3d(original_q) * original_p;
 
  162     updated_q = original_q * diff_q;
 
  164     updated_q = diff_q * original_q;
 
  166   pose_.position.x += original_p[0];
 
  167   pose_.position.y += original_p[1];
 
  168   pose_.position.z += original_p[2];
 
  186     marker_.type = visualization_msgs::Marker::CYLINDER;
 
  187     type_ = jsk_rviz_plugins::TransformableMarkerOperate::CYLINDER;
 
  209   TransformableTorus::TransformableTorus( 
float radius, 
float small_radius, 
int u_div, 
int v_div, 
float r, 
float g, 
float b, 
float a, std::string frame, std::string name, std::string description){
 
  216     marker_.type = visualization_msgs::Marker::TRIANGLE_LIST;
 
  217     type_ = jsk_rviz_plugins::TransformableMarkerOperate::TORUS;
 
  228     std::vector<geometry_msgs::Point> triangle_mesh;
 
  233     std::vector<std::vector<geometry_msgs::Point> > points_array;
 
  234     for (
int i = 0; 
i < u_division_num; 
i ++){
 
  235       std::vector<geometry_msgs::Point> points;
 
  238       for (
int j = 0; j < v_division_num; j++){
 
  239         geometry_msgs::Point new_point;
 
  243         points.push_back(new_point);
 
  245       points_array.push_back(points);
 
  249     for(
int i = 0; 
i < u_division_num; 
i++){
 
  250       std::vector<geometry_msgs::Point> target_points = points_array[
i];
 
  251       float prev_index = 
i - 1, next_index = 
i + 1;
 
  253         prev_index = u_division_num - 1;
 
  254       if(next_index > u_division_num - 1)
 
  256       std::vector<geometry_msgs::Point> prev_points = points_array[prev_index];
 
  257       std::vector<geometry_msgs::Point> next_points = points_array[next_index];
 
  258       for(
int j = 0; j < v_division_num; j++){
 
  259         float next_point_index = j + 1;
 
  260         if( next_point_index > v_division_num - 1)
 
  261           next_point_index = 0;
 
  263         triangle_mesh.push_back(target_points[j]);
 
  264         triangle_mesh.push_back(next_points[j]);
 
  265         triangle_mesh.push_back(target_points[next_point_index]);
 
  267         triangle_mesh.push_back(target_points[j]);
 
  268         triangle_mesh.push_back(target_points[next_point_index]);
 
  269         triangle_mesh.push_back(prev_points[next_point_index]);
 
  273     return triangle_mesh;
 
  295     marker_.type = visualization_msgs::Marker::CUBE;
 
  310     marker_.type = visualization_msgs::Marker::CUBE;
 
  311     type_ = jsk_rviz_plugins::TransformableMarkerOperate::BOX;
 
  334     marker_.type = visualization_msgs::Marker::MESH_RESOURCE;
 
  335     type_ = jsk_rviz_plugins::TransformableMarkerOperate::MESH_RESOURCE;