basic_controls.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 
31 #include <ros/ros.h>
32 
35 
37 #include <tf/tf.h>
38 
39 #include <math.h>
40 
41 using namespace visualization_msgs;
42 
43 
44 // %Tag(vars)%
47 // %EndTag(vars)%
48 
49 
50 // %Tag(Box)%
51 Marker makeBox( InteractiveMarker &msg )
52 {
53  Marker marker;
54 
55  marker.type = Marker::CUBE;
56  marker.scale.x = msg.scale * 0.45;
57  marker.scale.y = msg.scale * 0.45;
58  marker.scale.z = msg.scale * 0.45;
59  marker.color.r = 0.5;
60  marker.color.g = 0.5;
61  marker.color.b = 0.5;
62  marker.color.a = 1.0;
63 
64  return marker;
65 }
66 
67 InteractiveMarkerControl& makeBoxControl( InteractiveMarker &msg )
68 {
69  InteractiveMarkerControl control;
70  control.always_visible = true;
71  control.markers.push_back( makeBox(msg) );
72  msg.controls.push_back( control );
73 
74  return msg.controls.back();
75 }
76 // %EndTag(Box)%
77 
78 // %Tag(frameCallback)%
80 {
81  static uint32_t counter = 0;
82 
84 
85  tf::Transform t;
86 
87  ros::Time time = ros::Time::now();
88 
89  t.setOrigin(tf::Vector3(0.0, 0.0, sin(float(counter)/140.0) * 2.0));
90  t.setRotation(tf::Quaternion(0.0, 0.0, 0.0, 1.0));
91  br.sendTransform(tf::StampedTransform(t, time, "base_link", "moving_frame"));
92 
93  t.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
94  t.setRotation(tf::createQuaternionFromRPY(0.0, float(counter)/140.0, 0.0));
95  br.sendTransform(tf::StampedTransform(t, time, "base_link", "rotating_frame"));
96 
97  counter++;
98 }
99 // %EndTag(frameCallback)%
100 
101 // %Tag(processFeedback)%
102 void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
103 {
104  std::ostringstream s;
105  s << "Feedback from marker '" << feedback->marker_name << "' "
106  << " / control '" << feedback->control_name << "'";
107 
108  std::ostringstream mouse_point_ss;
109  if( feedback->mouse_point_valid )
110  {
111  mouse_point_ss << " at " << feedback->mouse_point.x
112  << ", " << feedback->mouse_point.y
113  << ", " << feedback->mouse_point.z
114  << " in frame " << feedback->header.frame_id;
115  }
116 
117  switch ( feedback->event_type )
118  {
119  case visualization_msgs::InteractiveMarkerFeedback::BUTTON_CLICK:
120  ROS_INFO_STREAM( s.str() << ": button click" << mouse_point_ss.str() << "." );
121  break;
122 
123  case visualization_msgs::InteractiveMarkerFeedback::MENU_SELECT:
124  ROS_INFO_STREAM( s.str() << ": menu item " << feedback->menu_entry_id << " clicked" << mouse_point_ss.str() << "." );
125  break;
126 
127  case visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE:
128  ROS_INFO_STREAM( s.str() << ": pose changed"
129  << "\nposition = "
130  << feedback->pose.position.x
131  << ", " << feedback->pose.position.y
132  << ", " << feedback->pose.position.z
133  << "\norientation = "
134  << feedback->pose.orientation.w
135  << ", " << feedback->pose.orientation.x
136  << ", " << feedback->pose.orientation.y
137  << ", " << feedback->pose.orientation.z
138  << "\nframe: " << feedback->header.frame_id
139  << " time: " << feedback->header.stamp.sec << "sec, "
140  << feedback->header.stamp.nsec << " nsec" );
141  break;
142 
143  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_DOWN:
144  ROS_INFO_STREAM( s.str() << ": mouse down" << mouse_point_ss.str() << "." );
145  break;
146 
147  case visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP:
148  ROS_INFO_STREAM( s.str() << ": mouse up" << mouse_point_ss.str() << "." );
149  break;
150  }
151 
152  server->applyChanges();
153 }
154 // %EndTag(processFeedback)%
155 
156 // %Tag(alignMarker)%
157 void alignMarker( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
158 {
159  geometry_msgs::Pose pose = feedback->pose;
160 
161  pose.position.x = round(pose.position.x-0.5)+0.5;
162  pose.position.y = round(pose.position.y-0.5)+0.5;
163 
164  ROS_INFO_STREAM( feedback->marker_name << ":"
165  << " aligning position = "
166  << feedback->pose.position.x
167  << ", " << feedback->pose.position.y
168  << ", " << feedback->pose.position.z
169  << " to "
170  << pose.position.x
171  << ", " << pose.position.y
172  << ", " << pose.position.z );
173 
174  server->setPose( feedback->marker_name, pose );
175  server->applyChanges();
176 }
177 // %EndTag(alignMarker)%
178 
179 double rand( double min, double max )
180 {
181  double t = (double)rand() / (double)RAND_MAX;
182  return min + t*(max-min);
183 }
184 
186 
187 // %Tag(6DOF)%
188 void make6DofMarker( bool fixed, unsigned int interaction_mode, const tf::Vector3& position, bool show_6dof )
189 {
190  InteractiveMarker int_marker;
191  int_marker.header.frame_id = "base_link";
192  tf::pointTFToMsg(position, int_marker.pose.position);
193  int_marker.scale = 1;
194 
195  int_marker.name = "simple_6dof";
196  int_marker.description = "Simple 6-DOF Control";
197 
198  // insert a box
199  makeBoxControl(int_marker);
200  int_marker.controls[0].interaction_mode = interaction_mode;
201 
202  InteractiveMarkerControl control;
203 
204  if ( fixed )
205  {
206  int_marker.name += "_fixed";
207  int_marker.description += "\n(fixed orientation)";
208  control.orientation_mode = InteractiveMarkerControl::FIXED;
209  }
210 
211  if (interaction_mode != visualization_msgs::InteractiveMarkerControl::NONE)
212  {
213  std::string mode_text;
214  if( interaction_mode == visualization_msgs::InteractiveMarkerControl::MOVE_3D ) mode_text = "MOVE_3D";
215  if( interaction_mode == visualization_msgs::InteractiveMarkerControl::ROTATE_3D ) mode_text = "ROTATE_3D";
216  if( interaction_mode == visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D ) mode_text = "MOVE_ROTATE_3D";
217  int_marker.name += "_" + mode_text;
218  int_marker.description = std::string("3D Control") + (show_6dof ? " + 6-DOF controls" : "") + "\n" + mode_text;
219  }
220 
221  if(show_6dof)
222  {
223  tf::Quaternion orien(1.0, 0.0, 0.0, 1.0);
224  orien.normalize();
225  tf::quaternionTFToMsg(orien, control.orientation);
226  control.name = "rotate_x";
227  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
228  int_marker.controls.push_back(control);
229  control.name = "move_x";
230  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
231  int_marker.controls.push_back(control);
232 
233  orien = tf::Quaternion(0.0, 1.0, 0.0, 1.0);
234  orien.normalize();
235  tf::quaternionTFToMsg(orien, control.orientation);
236  control.name = "rotate_z";
237  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
238  int_marker.controls.push_back(control);
239  control.name = "move_z";
240  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
241  int_marker.controls.push_back(control);
242 
243  orien = tf::Quaternion(0.0, 0.0, 1.0, 1.0);
244  orien.normalize();
245  tf::quaternionTFToMsg(orien, control.orientation);
246  control.name = "rotate_y";
247  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
248  int_marker.controls.push_back(control);
249  control.name = "move_y";
250  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
251  int_marker.controls.push_back(control);
252  }
253 
254  server->insert(int_marker);
255  server->setCallback(int_marker.name, &processFeedback);
256  if (interaction_mode != visualization_msgs::InteractiveMarkerControl::NONE)
257  menu_handler.apply( *server, int_marker.name );
258 }
259 // %EndTag(6DOF)%
260 
261 // %Tag(RandomDof)%
263 {
264  InteractiveMarker int_marker;
265  int_marker.header.frame_id = "base_link";
266  tf::pointTFToMsg(position, int_marker.pose.position);
267  int_marker.scale = 1;
268 
269  int_marker.name = "6dof_random_axes";
270  int_marker.description = "6-DOF\n(Arbitrary Axes)";
271 
272  makeBoxControl(int_marker);
273 
274  InteractiveMarkerControl control;
275 
276  for ( int i=0; i<3; i++ )
277  {
278  tf::Quaternion orien(rand(-1,1), rand(-1,1), rand(-1,1), rand(-1,1));
279  orien.normalize();
280  tf::quaternionTFToMsg(orien, control.orientation);
281  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
282  int_marker.controls.push_back(control);
283  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
284  int_marker.controls.push_back(control);
285  }
286 
287  server->insert(int_marker);
288  server->setCallback(int_marker.name, &processFeedback);
289 }
290 // %EndTag(RandomDof)%
291 
292 
293 // %Tag(ViewFacing)%
295 {
296  InteractiveMarker int_marker;
297  int_marker.header.frame_id = "base_link";
298  tf::pointTFToMsg(position, int_marker.pose.position);
299  int_marker.scale = 1;
300 
301  int_marker.name = "view_facing";
302  int_marker.description = "View Facing 6-DOF";
303 
304  InteractiveMarkerControl control;
305 
306  // make a control that rotates around the view axis
307  control.orientation_mode = InteractiveMarkerControl::VIEW_FACING;
308  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
309  control.orientation.w = 1;
310  control.name = "rotate";
311 
312  int_marker.controls.push_back(control);
313 
314  // create a box in the center which should not be view facing,
315  // but move in the camera plane.
316  control.orientation_mode = InteractiveMarkerControl::VIEW_FACING;
317  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
318  control.independent_marker_orientation = true;
319  control.name = "move";
320 
321  control.markers.push_back( makeBox(int_marker) );
322  control.always_visible = true;
323 
324  int_marker.controls.push_back(control);
325 
326  server->insert(int_marker);
327  server->setCallback(int_marker.name, &processFeedback);
328 }
329 // %EndTag(ViewFacing)%
330 
331 
332 // %Tag(Quadrocopter)%
334 {
335  InteractiveMarker int_marker;
336  int_marker.header.frame_id = "base_link";
337  tf::pointTFToMsg(position, int_marker.pose.position);
338  int_marker.scale = 1;
339 
340  int_marker.name = "quadrocopter";
341  int_marker.description = "Quadrocopter";
342 
343  makeBoxControl(int_marker);
344 
345  InteractiveMarkerControl control;
346 
347  tf::Quaternion orien(0.0, 1.0, 0.0, 1.0);
348  orien.normalize();
349  tf::quaternionTFToMsg(orien, control.orientation);
350  control.interaction_mode = InteractiveMarkerControl::MOVE_ROTATE;
351  int_marker.controls.push_back(control);
352  control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
353  int_marker.controls.push_back(control);
354 
355  server->insert(int_marker);
356  server->setCallback(int_marker.name, &processFeedback);
357 }
358 // %EndTag(Quadrocopter)%
359 
360 // %Tag(ChessPiece)%
362 {
363  InteractiveMarker int_marker;
364  int_marker.header.frame_id = "base_link";
365  tf::pointTFToMsg(position, int_marker.pose.position);
366  int_marker.scale = 1;
367 
368  int_marker.name = "chess_piece";
369  int_marker.description = "Chess Piece\n(2D Move + Alignment)";
370 
371  InteractiveMarkerControl control;
372 
373  tf::Quaternion orien(0.0, 1.0, 0.0, 1.0);
374  orien.normalize();
375  tf::quaternionTFToMsg(orien, control.orientation);
376  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
377  int_marker.controls.push_back(control);
378 
379  // make a box which also moves in the plane
380  control.markers.push_back( makeBox(int_marker) );
381  control.always_visible = true;
382  int_marker.controls.push_back(control);
383 
384  // we want to use our special callback function
385  server->insert(int_marker);
386  server->setCallback(int_marker.name, &processFeedback);
387 
388  // set different callback for POSE_UPDATE feedback
389  server->setCallback(int_marker.name, &alignMarker, visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE );
390 }
391 // %EndTag(ChessPiece)%
392 
393 // %Tag(PanTilt)%
395 {
396  InteractiveMarker int_marker;
397  int_marker.header.frame_id = "base_link";
398  tf::pointTFToMsg(position, int_marker.pose.position);
399  int_marker.scale = 1;
400 
401  int_marker.name = "pan_tilt";
402  int_marker.description = "Pan / Tilt";
403 
404  makeBoxControl(int_marker);
405 
406  InteractiveMarkerControl control;
407 
408  tf::Quaternion orien(0.0, 1.0, 0.0, 1.0);
409  orien.normalize();
410  tf::quaternionTFToMsg(orien, control.orientation);
411  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
412  control.orientation_mode = InteractiveMarkerControl::FIXED;
413  int_marker.controls.push_back(control);
414 
415  orien = tf::Quaternion(0.0, 0.0, 1.0, 1.0);
416  orien.normalize();
417  tf::quaternionTFToMsg(orien, control.orientation);
418  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
419  control.orientation_mode = InteractiveMarkerControl::INHERIT;
420  int_marker.controls.push_back(control);
421 
422  server->insert(int_marker);
423  server->setCallback(int_marker.name, &processFeedback);
424 }
425 // %EndTag(PanTilt)%
426 
427 // %Tag(Menu)%
429 {
430  InteractiveMarker int_marker;
431  int_marker.header.frame_id = "base_link";
432  tf::pointTFToMsg(position, int_marker.pose.position);
433  int_marker.scale = 1;
434 
435  int_marker.name = "context_menu";
436  int_marker.description = "Context Menu\n(Right Click)";
437 
438  InteractiveMarkerControl control;
439 
440  control.interaction_mode = InteractiveMarkerControl::MENU;
441  control.name = "menu_only_control";
442 
443  Marker marker = makeBox( int_marker );
444  control.markers.push_back( marker );
445  control.always_visible = true;
446  int_marker.controls.push_back(control);
447 
448  server->insert(int_marker);
449  server->setCallback(int_marker.name, &processFeedback);
450  menu_handler.apply( *server, int_marker.name );
451 }
452 // %EndTag(Menu)%
453 
454 // %Tag(Button)%
456 {
457  InteractiveMarker int_marker;
458  int_marker.header.frame_id = "base_link";
459  tf::pointTFToMsg(position, int_marker.pose.position);
460  int_marker.scale = 1;
461 
462  int_marker.name = "button";
463  int_marker.description = "Button\n(Left Click)";
464 
465  InteractiveMarkerControl control;
466 
467  control.interaction_mode = InteractiveMarkerControl::BUTTON;
468  control.name = "button_control";
469 
470  Marker marker = makeBox( int_marker );
471  control.markers.push_back( marker );
472  control.always_visible = true;
473  int_marker.controls.push_back(control);
474 
475  server->insert(int_marker);
476  server->setCallback(int_marker.name, &processFeedback);
477 }
478 // %EndTag(Button)%
479 
480 // %Tag(Moving)%
482 {
483  InteractiveMarker int_marker;
484  int_marker.header.frame_id = "moving_frame";
485  tf::pointTFToMsg(position, int_marker.pose.position);
486  int_marker.scale = 1;
487 
488  int_marker.name = "moving";
489  int_marker.description = "Marker Attached to a\nMoving Frame";
490 
491  InteractiveMarkerControl control;
492 
493  tf::Quaternion orien(1.0, 0.0, 0.0, 1.0);
494  orien.normalize();
495  tf::quaternionTFToMsg(orien, control.orientation);
496  control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
497  int_marker.controls.push_back(control);
498 
499  control.interaction_mode = InteractiveMarkerControl::MOVE_PLANE;
500  control.always_visible = true;
501  control.markers.push_back( makeBox(int_marker) );
502  int_marker.controls.push_back(control);
503 
504  server->insert(int_marker);
505  server->setCallback(int_marker.name, &processFeedback);
506 }
507 // %EndTag(Moving)%
508 
509 // %Tag(main)%
510 int main(int argc, char** argv)
511 {
512  ros::init(argc, argv, "basic_controls");
513  ros::NodeHandle n;
514 
515  // create a timer to update the published transforms
516  ros::Timer frame_timer = n.createTimer(ros::Duration(0.01), frameCallback);
517 
518  server.reset( new interactive_markers::InteractiveMarkerServer("basic_controls","",false) );
519 
520  ros::Duration(0.1).sleep();
521 
522  menu_handler.insert( "First Entry", &processFeedback );
523  menu_handler.insert( "Second Entry", &processFeedback );
525  menu_handler.insert( sub_menu_handle, "First Entry", &processFeedback );
526  menu_handler.insert( sub_menu_handle, "Second Entry", &processFeedback );
527 
529  position = tf::Vector3(-3, 3, 0);
530  make6DofMarker( false, visualization_msgs::InteractiveMarkerControl::NONE, position, true );
531  position = tf::Vector3( 0, 3, 0);
532  make6DofMarker( true, visualization_msgs::InteractiveMarkerControl::NONE, position, true );
533  position = tf::Vector3( 3, 3, 0);
534  makeRandomDofMarker( position );
535  position = tf::Vector3(-3, 0, 0);
536  make6DofMarker( false, visualization_msgs::InteractiveMarkerControl::ROTATE_3D, position, false );
537  position = tf::Vector3( 0, 0, 0);
538  make6DofMarker( false, visualization_msgs::InteractiveMarkerControl::MOVE_ROTATE_3D, position, true );
539  position = tf::Vector3( 3, 0, 0);
540  make6DofMarker( false, visualization_msgs::InteractiveMarkerControl::MOVE_3D, position, false );
541  position = tf::Vector3(-3,-3, 0);
542  makeViewFacingMarker( position );
543  position = tf::Vector3( 0,-3, 0);
544  makeQuadrocopterMarker( position );
545  position = tf::Vector3( 3,-3, 0);
546  makeChessPieceMarker( position );
547  position = tf::Vector3(-3,-6, 0);
548  makePanTiltMarker( position );
549  position = tf::Vector3( 0,-6, 0);
550  makeMovingMarker( position );
551  position = tf::Vector3( 3,-6, 0);
552  makeMenuMarker( position );
553  position = tf::Vector3( 0,-9, 0);
554  makeButtonMarker( position );
555 
556  server->applyChanges();
557 
558  ros::spin();
559 
560  server.reset();
561 }
562 // %EndTag(main)%
static tf::Quaternion createQuaternionFromRPY(double roll, double pitch, double yaw)
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
void makePanTiltMarker(const tf::Vector3 &position)
void processFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
interactive_markers::MenuHandler menu_handler
void makeMovingMarker(const tf::Vector3 &position)
XmlRpcServer s
bool sleep() const
void alignMarker(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Quaternion & normalize()
void makeButtonMarker(const tf::Vector3 &position)
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
ROSCPP_DECL void spin(Spinner &spinner)
void makeQuadrocopterMarker(const tf::Vector3 &position)
InteractiveMarkerControl & makeBoxControl(InteractiveMarker &msg)
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
void makeViewFacingMarker(const tf::Vector3 &position)
void makeChessPieceMarker(const tf::Vector3 &position)
void frameCallback(const ros::TimerEvent &)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void sendTransform(const StampedTransform &transform)
int main(int argc, char **argv)
void makeMenuMarker(const tf::Vector3 &position)
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
#define ROS_INFO_STREAM(args)
Marker makeBox(InteractiveMarker &msg)
void makeRandomDofMarker(const tf::Vector3 &position)
static Time now()
double rand(double min, double max)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void make6DofMarker(bool fixed, unsigned int interaction_mode, const tf::Vector3 &position, bool show_6dof)
static void pointTFToMsg(const Point &bt_v, geometry_msgs::Point &msg_v)


interactive_marker_tutorials
Author(s): David Gossow
autogenerated on Fri Feb 1 2019 03:33:34