transformable_object.cpp
Go to the documentation of this file.
3 #include <math.h>
4 
5 #define PI 3.14159265
6 
7 using namespace jsk_interactive_marker;
8 
9 inline geometry_msgs::Pose inverse(geometry_msgs::Pose pose){
10  Eigen::Affine3d pose_eigen;
11  tf::poseMsgToEigen(pose, pose_eigen);
12  tf::poseEigenToMsg(pose_eigen.inverse(), pose);
13  return pose;
14 }
15 
16 
18  ROS_INFO("Init TransformableObject");
19  control_offset_pose_.orientation.x = 0;
20  control_offset_pose_.orientation.y = 0;
21  control_offset_pose_.orientation.z = 0;
22  control_offset_pose_.orientation.w = 1;
25  display_description_ = true;
26 }
27 
29 {
31 }
32 
34 {
36 }
37 
38 void TransformableObject::setInteractiveMarkerSetting(const InteractiveSettingConfig& config){
39  display_interactive_manipulator_ = config.display_interactive_manipulator;
40  display_description_ = config.display_description_only_selected ? false : true;
41  interactive_manipulator_orientation_ = config.interactive_manipulator_orientation;
42  interaction_mode_ = static_cast<unsigned int>(config.interaction_mode);
43 }
44 
45 std::vector<visualization_msgs::InteractiveMarkerControl> TransformableObject::makeRotateTransFixControl(unsigned int orientation_mode){
46  visualization_msgs::InteractiveMarkerControl control;
47 
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);
60 
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);
71 
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);
82 
83  return controls;
84 };
85 
86 void TransformableObject::addMarker(visualization_msgs::InteractiveMarker &int_marker, bool always_visible, unsigned int interaction_mode)
87 {
88  visualization_msgs::Marker marker = getVisualizationMsgMarker();
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);
94 };
95 
96 void TransformableObject::addControl(visualization_msgs::InteractiveMarker &int_marker)
97 {
99  std::vector<visualization_msgs::InteractiveMarkerControl> rotate_controls = makeRotateTransFixControl(interactive_manipulator_orientation_);
100  int_marker.controls.insert(int_marker.controls.end(), rotate_controls.begin(), rotate_controls.end());
101  }
102 };
103 
104 visualization_msgs::InteractiveMarker TransformableObject::getInteractiveMarker(){
105  visualization_msgs::InteractiveMarker int_marker;
106 
107  addMarker(int_marker, true, interaction_mode_);
108  addControl(int_marker);
109  int_marker.header.frame_id = frame_id_;
110  int_marker.name = name_;
111  if (display_description_) {
112  int_marker.description = description_;
113  } else {
114  int_marker.description = "";
115  }
116  int_marker.pose = pose_;
117  int_marker.scale = getInteractiveMarkerScale();
118  return int_marker;
119 };
120 
121 void TransformableObject::setPose(geometry_msgs::Pose pose, bool for_interactive_control){
122  if(for_interactive_control) {
123  pose_ = pose;
124  }
125  else {
126  Eigen::Affine3d control_offset_eigen;
127  tf::poseMsgToEigen(control_offset_pose_, control_offset_eigen);
128  Eigen::Affine3d pose_eigen;
129  tf::poseMsgToEigen(pose, pose_eigen);
130  tf::poseEigenToMsg(pose_eigen * control_offset_eigen, pose_);
131  }
132 }
133 
134 geometry_msgs::Pose TransformableObject::getPose(bool for_interactive_control){
135  if(for_interactive_control) {
136  return pose_;
137  }
138  else{
139  geometry_msgs::Pose pose;
140  Eigen::Affine3d control_offset_eigen;
141  tf::poseMsgToEigen(control_offset_pose_, control_offset_eigen);
142  Eigen::Affine3d pose_eigen;
143  tf::poseMsgToEigen(pose_, pose_eigen);
144  tf::poseEigenToMsg(pose_eigen * control_offset_eigen.inverse(), pose);
145  //return pose;
146  return pose;
147  }
148 }
149 
150 
151 void TransformableObject::addPose(geometry_msgs::Pose msg, bool relative){
152  Eigen::Vector3d original_p(msg.position.x, msg.position.y, msg.position.z);
153  Eigen::Quaterniond original_q;
154  tf::quaternionMsgToEigen(pose_.orientation, original_q);
155  Eigen::Quaterniond diff_q;
156  tf::quaternionMsgToEigen(msg.orientation, diff_q);
157  Eigen::Quaterniond updated_q;
158  if(relative) {
159  original_p = Eigen::Affine3d(original_q) * original_p;
160  }
161  if(relative) {
162  updated_q = original_q * diff_q;
163  } else {
164  updated_q = diff_q * original_q;
165  }
166  pose_.position.x += original_p[0];
167  pose_.position.y += original_p[1];
168  pose_.position.z += original_p[2];
169  tf::quaternionEigenToMsg(updated_q, pose_.orientation);
170 }
171 
173  tf::Transform transform;
174  tf::poseMsgToTF(getPose(), transform);
176 }
177 
178 namespace jsk_interactive_marker{
179  TransformableCylinder::TransformableCylinder( float radius, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description){
180  cylinder_radius_ = radius;
181  cylinder_z_ = z;
182  cylinder_r_ = r;
183  cylinder_g_ = g;
184  cylinder_b_ = b;
185  cylinder_a_ = a;
186  marker_.type = visualization_msgs::Marker::CYLINDER;
187  type_ = jsk_rviz_plugins::TransformableMarkerOperate::CYLINDER;
188 
189  frame_id_ = frame;
190  name_ = name;
191  description_ = description;
192  }
193 
195  marker_.scale.x = cylinder_radius_ * 2.0;
196  marker_.scale.y = cylinder_radius_ * 2.0;
197  marker_.scale.z = cylinder_z_;
198  marker_.color.r = cylinder_r_;
199  marker_.color.g = cylinder_g_;
200  marker_.color.b = cylinder_b_;
201  marker_.color.a = cylinder_a_;
203  return marker_;
204  }
205 }
206 
207 namespace jsk_interactive_marker{
208 
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){
210  torus_radius_ = radius;
211  torus_small_radius_ = small_radius;
212  torus_r_ = r;
213  torus_g_ = g;
214  torus_b_ = b;
215  torus_a_ = a;
216  marker_.type = visualization_msgs::Marker::TRIANGLE_LIST;
217  type_ = jsk_rviz_plugins::TransformableMarkerOperate::TORUS;
218 
219  frame_id_ = frame;
220  name_ = name;
221  description_ = description;
222 
223  u_division_num_ = u_div;
224  v_division_num_ = v_div;
225  }
226 
227  std::vector<geometry_msgs::Point > TransformableTorus::calcurateTriangleMesh(){
228  std::vector<geometry_msgs::Point> triangle_mesh;
229  float center_x = 0;
230  float center_y = 0;
231  float u_division_num = u_division_num_;
232  float v_division_num = v_division_num_;
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;
236  float target_circle_x = torus_radius_ * cos( ( i / u_division_num) * 2 * PI) ;
237  float target_circle_y = torus_radius_ * sin( ( i / u_division_num) * 2 * PI) ;
238  for (int j = 0; j < v_division_num; j++){
239  geometry_msgs::Point new_point;
240  new_point.x = target_circle_x + torus_small_radius_ * cos ( (j / v_division_num) * 2 * PI) * cos( ( i / u_division_num) * 2 * PI);
241  new_point.y = target_circle_y + torus_small_radius_ * cos ( (j / v_division_num) * 2 * PI) * sin( ( i / u_division_num) * 2 * PI);
242  new_point.z = torus_small_radius_ * sin ( (j / v_division_num) * 2 * PI);
243  points.push_back(new_point);
244  }
245  points_array.push_back(points);
246  }
247 
248  //create mesh list;
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;
252  if(prev_index < 0)
253  prev_index = u_division_num - 1;
254  if(next_index > u_division_num - 1)
255  next_index = 0;
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;
262  //first pushes
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]);
266  //second pushes
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]);
270  }
271  }
272 
273  return triangle_mesh;
274  }
275 
276  visualization_msgs::Marker TransformableTorus::getVisualizationMsgMarker(){
277  marker_.points = calcurateTriangleMesh();
278  marker_.color.r = torus_r_;
279  marker_.color.g = torus_g_;
280  marker_.color.b = torus_b_;
281  marker_.color.a = torus_a_;
282  return marker_;
283  }
284 }
285 
286 namespace jsk_interactive_marker{
287 
288  TransformableBox::TransformableBox( float length , float r, float g, float b, float a, std::string frame, std::string name, std::string description){
289  box_x_ = box_y_ = box_z_ = length;
290 
291  box_r_ = r;
292  box_g_ = g;
293  box_b_ = b;
294  box_a_ = a;
295  marker_.type = visualization_msgs::Marker::CUBE;
296 
297  frame_id_ = frame;
298  name_ = name;
299  description_ = description;
300  }
301 
302  TransformableBox::TransformableBox( float x, float y, float z , float r, float g, float b, float a, std::string frame, std::string name, std::string description){
303  box_x_ = x;
304  box_y_ = y;
305  box_z_ = z;
306  box_r_ = r;
307  box_g_ = g;
308  box_b_ = b;
309  box_a_ = a;
310  marker_.type = visualization_msgs::Marker::CUBE;
311  type_ = jsk_rviz_plugins::TransformableMarkerOperate::BOX;
312 
313  frame_id_ = frame;
314  name_ = name;
315  description_ = description;
316  }
317 
318  visualization_msgs::Marker TransformableBox::getVisualizationMsgMarker(){
319  marker_.scale.x = box_x_;
320  marker_.scale.y = box_y_;
321  marker_.scale.z = box_z_;
322  marker_.color.r = box_r_;
323  marker_.color.g = box_g_;
324  marker_.color.b = box_b_;
325  marker_.color.a = box_a_;
326  return marker_;
327  }
328 }
329 
330 namespace jsk_interactive_marker{
331 
332  TransformableMesh::TransformableMesh( std::string frame, std::string name, std::string description, std::string mesh_resource, bool mesh_use_embedded_materials){
333  marker_scale_ = 0.5;
334  marker_.type = visualization_msgs::Marker::MESH_RESOURCE;
335  type_ = jsk_rviz_plugins::TransformableMarkerOperate::MESH_RESOURCE;
336  mesh_resource_ = mesh_resource;
337  mesh_use_embedded_materials_ = mesh_use_embedded_materials;
338  frame_id_ = frame;
339  name_ = name;
340  description_ = description;
341  }
342 
343  visualization_msgs::Marker TransformableMesh::getVisualizationMsgMarker(){
344  marker_.mesh_resource = mesh_resource_;
345  marker_.mesh_use_embedded_materials = mesh_use_embedded_materials_;
346  marker_.scale.x = 1.0;
347  marker_.scale.y = 1.0;
348  marker_.scale.z = 1.0;
349  marker_.color.r = mesh_r_;
350  marker_.color.g = mesh_g_;
351  marker_.color.b = mesh_b_;
352  marker_.color.a = mesh_a_;
354  return marker_;
355  }
356 }
TransformableCylinder(float radius, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description)
std::vector< geometry_msgs::Point > calcurateTriangleMesh()
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
geometry_msgs::Pose getPose(bool for_interactive_control=false)
visualization_msgs::Marker getVisualizationMsgMarker()
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
double cos()
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
double sin()
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
#define PI
void addControl(visualization_msgs::InteractiveMarker &int_marker)
void addMarker(visualization_msgs::InteractiveMarker &int_marker, bool always_visible=true, unsigned int interaction_mode=visualization_msgs::InteractiveMarkerControl::MOVE_3D)
pose
visualization_msgs::Marker getVisualizationMsgMarker()
std::vector< visualization_msgs::InteractiveMarkerControl > makeRotateTransFixControl(unsigned int orientation_mode=visualization_msgs::InteractiveMarkerControl::FIXED)
void setPose(geometry_msgs::Pose pose, bool for_interactive_control=false)
TransformableBox(float length, float r, float g, float b, float a, std::string frame, std::string name, std::string description)
void addPose(geometry_msgs::Pose msg, bool relative=false)
#define ROS_INFO(...)
void sendTransform(const StampedTransform &transform)
visualization_msgs::Marker getVisualizationMsgMarker()
TransformableMesh(std::string frame, std::string name, std::string description, std::string mesh_resource, bool mesh_use_embedded_materials)
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)
void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
static Time now()
virtual visualization_msgs::Marker getVisualizationMsgMarker()
void setInteractiveMarkerSetting(const InteractiveSettingConfig &config)
geometry_msgs::Pose inverse(geometry_msgs::Pose pose)
visualization_msgs::InteractiveMarker getInteractiveMarker()


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