marker_6dof.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015-2016, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <ros/ros.h>
41 #include <tf/transform_listener.h>
42 #include <geometry_msgs/PoseStamped.h>
45 
46 class Marker6DOF {
47 public:
49  ros::NodeHandle nh, pnh("~");
50  pnh.param("publish_tf", publish_tf_, false);
51  pnh.param("publish_pose_periodically", publish_pose_periodically_, false);
52  pnh.param("tf_frame", tf_frame_, std::string("object"));
53  double tf_duration;
54  pnh.param("tf_duration", tf_duration, 0.1);
55  pnh.param("object_type", object_type_, std::string("sphere"));
56  pnh.param("object_x", object_x_, 1.0);
57  pnh.param("object_y", object_y_, 1.0);
58  pnh.param("object_z", object_z_, 1.0);
59  pnh.param("object_r", object_r_, 1.0);
60  pnh.param("object_g", object_g_, 1.0);
61  pnh.param("object_b", object_b_, 1.0);
62  pnh.param("object_a", object_a_, 1.0);
63  std::string frame_id;
64  pnh.param("frame_id", frame_id, std::string("/map"));
65  latest_pose_.header.frame_id = frame_id;
66  double initial_x, initial_y, initial_z;
67  pnh.param("initial_x", initial_x, 0.0);
68  pnh.param("initial_y", initial_y, 0.0);
69  pnh.param("initial_z", initial_z, 0.0);
70  latest_pose_.pose.position.x = initial_x;
71  latest_pose_.pose.position.y = initial_y;
72  latest_pose_.pose.position.z = initial_z;
73  std::vector<double> initial_orientation;
74  if (jsk_topic_tools::readVectorParameter(pnh, "initial_orientation", initial_orientation)) {
75  latest_pose_.pose.orientation.x = initial_orientation[0];
76  latest_pose_.pose.orientation.y = initial_orientation[1];
77  latest_pose_.pose.orientation.z = initial_orientation[2];
78  latest_pose_.pose.orientation.w = initial_orientation[3];
79  }
80  else {
81  latest_pose_.pose.orientation.w = 1.0;
82  }
83  pnh.param("line_width", line_width_, 0.007);
84  pnh.param("mesh_file", mesh_file_, std::string(""));
85  if (pnh.hasParam("interactive_marker_scale")) {
86  pnh.param("interactive_marker_scale", int_marker_scale_, 1.0);
87  } else {
88  int_marker_scale_ = std::max(object_x_, std::max(object_y_, object_z_)) + 0.5;
89  }
90  if (publish_tf_) {
92  }
93 
94  pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("pose", 1);
95  pose_stamped_sub_ = pnh.subscribe("move_marker", 1, &Marker6DOF::moveMarkerCB, this);
96 
98  = menu_handler_.insert("Toggle 6DOF Circle",
99  boost::bind(&Marker6DOF::menuFeedbackCB, this, _1));
104  // Timer to update current pose on Rviz in the case which user re-enabled the plugin
105  timer_pose_ = nh.createTimer(ros::Duration(0.1), boost::bind(&Marker6DOF::timerPoseCallback, this, _1));
106  if (publish_tf_) {
107  timer_tf_ = nh.createTimer(ros::Duration(tf_duration), boost::bind(&Marker6DOF::timerTFCallback, this, _1));
108  }
109  }
110 
111 protected:
112  void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg) {
113  boost::mutex::scoped_lock lock(mutex_);
115  pose_pub_.publish(msg);
116  }
117  server_->setPose("marker", msg->pose, msg->header);
118  latest_pose_ = geometry_msgs::PoseStamped(*msg);
119  server_->applyChanges();
120  }
121 
122 
123  void calculateBoundingBox( visualization_msgs::Marker& object_marker){
124  geometry_msgs::Point top[5];
125  top[0].x = object_x_/2;
126  top[0].y = object_y_/2;
127  top[1].x = -object_x_/2;
128  top[1].y = object_y_/2;
129  top[2].x = -object_x_/2;
130  top[2].y = -object_y_/2;
131  top[3].x = object_x_/2;
132  top[3].y = -object_y_/2;
133  top[4].x = object_x_/2;
134  top[4].y = object_y_/2;
135 
136  geometry_msgs::Point bottom[5];
137  bottom[0].x = object_x_/2;
138  bottom[0].y = object_y_/2;
139  bottom[1].x = -object_x_/2;
140  bottom[1].y = object_y_/2;
141  bottom[2].x = -object_x_/2;
142  bottom[2].y = -object_y_/2;
143  bottom[3].x = object_x_/2;
144  bottom[3].y = -object_y_/2;
145  bottom[4].x = object_x_/2;
146  bottom[4].y = object_y_/2;
147 
148  for(int i = 0; i< 5; i++){
149  top[i].z = object_z_/2;
150  bottom[i].z = -object_z_/2;
151  }
152 
153  for(int i = 0; i< 4; i++){
154  object_marker.points.push_back(top[i]);
155  object_marker.points.push_back(top[i+1]);
156  object_marker.points.push_back(bottom[i]);
157  object_marker.points.push_back(bottom[i+1]);
158  object_marker.points.push_back(top[i]);
159  object_marker.points.push_back(bottom[i]);
160  }
161  }
162 
164  visualization_msgs::InteractiveMarker int_marker;
165  int_marker.header.frame_id = latest_pose_.header.frame_id;
166  int_marker.name = "marker";
167  int_marker.pose = geometry_msgs::Pose(latest_pose_.pose);
168 
169  visualization_msgs::Marker object_marker;
170  if(object_type_ == std::string("cube")){
171  object_marker.type = visualization_msgs::Marker::CUBE;
172  object_marker.scale.x = object_x_;
173  object_marker.scale.y = object_y_;
174  object_marker.scale.z = object_z_;
175  object_marker.color.r = object_r_;
176  object_marker.color.g = object_g_;
177  object_marker.color.b = object_b_;
178  object_marker.color.a = object_a_;
179  object_marker.pose.orientation.w = 1.0;
180  }
181  else if( object_type_ == std::string("sphere") ){
182  object_marker.type = visualization_msgs::Marker::SPHERE;
183  object_marker.scale.x = object_x_;
184  object_marker.scale.y = object_y_;
185  object_marker.scale.z = object_z_;
186  object_marker.color.r = object_r_;
187  object_marker.color.g = object_g_;
188  object_marker.color.b = object_b_;
189  object_marker.color.a = object_a_;
190  object_marker.pose.orientation.w = 1.0;
191  }
192  else if(object_type_ == std::string("line")){
193  object_marker.type = visualization_msgs::Marker::LINE_LIST;
194  object_marker.scale.x = line_width_;
195  object_marker.color.r = object_r_;
196  object_marker.color.g = object_g_;
197  object_marker.color.b = object_b_;
198  object_marker.color.a = object_a_;
199  object_marker.pose.orientation.w = 1.0;
200  calculateBoundingBox(object_marker);
201  }
202  else if(object_type_ == std::string("mesh")){
203  object_marker.type = visualization_msgs::Marker::MESH_RESOURCE;
204  object_marker.scale.x = object_x_;
205  object_marker.scale.y = object_y_;
206  object_marker.scale.z = object_z_;
207  object_marker.color.r = object_r_;
208  object_marker.color.g = object_g_;
209  object_marker.color.b = object_b_;
210  object_marker.color.a = object_a_;
211  object_marker.pose.orientation.w = 1.0;
212  object_marker.mesh_resource = mesh_file_;
213  }
214 
215 
216  visualization_msgs::InteractiveMarkerControl object_marker_control;
217  object_marker_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
218  object_marker_control.always_visible = true;
219  object_marker_control.markers.push_back(object_marker);
220  int_marker.controls.push_back(object_marker_control);
221 
222  visualization_msgs::InteractiveMarkerControl control;
223  if (show_6dof_circle_) {
224  control.orientation.w = 1;
225  control.orientation.x = 1;
226  control.orientation.y = 0;
227  control.orientation.z = 0;
228 
229  control.name = "rotate_x";
230  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
231  int_marker.controls.push_back(control);
232  control.name = "move_x";
233  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
234  int_marker.controls.push_back(control);
235 
236  control.orientation.w = 1;
237  control.orientation.x = 0;
238  control.orientation.y = 1;
239  control.orientation.z = 0;
240  control.name = "rotate_z";
241  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
242  int_marker.controls.push_back(control);
243  control.name = "move_z";
244  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
245  int_marker.controls.push_back(control);
246 
247  control.orientation.w = 1;
248  control.orientation.x = 0;
249  control.orientation.y = 0;
250  control.orientation.z = 1;
251  control.name = "rotate_y";
252  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
253  int_marker.controls.push_back(control);
254  control.name = "move_y";
255  control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
256  int_marker.controls.push_back(control);
257  }
258 
259  int_marker.scale = int_marker_scale_;
260 
261  server_->insert(int_marker,
262  boost::bind(&Marker6DOF::processFeedbackCB, this, _1));
263 
264  menu_handler_.apply(*server_, "marker");
265  server_->applyChanges();
266  }
267 
268  void publishTF(const geometry_msgs::PoseStamped& pose) {
269  tf::Transform transform;
270  tf::poseMsgToTF(pose.pose, transform);
271  tf_broadcaster_->sendTransform(tf::StampedTransform(
272  transform, pose.header.stamp,
273  pose.header.frame_id,
274  tf_frame_));
275  }
276 
277  void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
278  boost::mutex::scoped_lock lock(mutex_);
279  geometry_msgs::PoseStamped pose;
280  pose.header = feedback->header;
281  pose.pose = feedback->pose;
282  latest_pose_ = pose;
284  pose_pub_.publish(pose);
285  }
286  }
287 
288  void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
290  if (show_6dof_circle_) {
293  }
294  else {
297  }
298  initializeInteractiveMarker(); // ok...?
299  }
300 
302  boost::mutex::scoped_lock lock(mutex_);
303  geometry_msgs::PoseStamped pose = latest_pose_;
304  pose.header.stamp = e.current_real;
305  server_->setPose("marker", pose.pose, pose.header);
306  server_->applyChanges();
308  pose_pub_.publish(pose);
309  }
310  }
311 
313  boost::mutex::scoped_lock lock(mutex_);
314  geometry_msgs::PoseStamped pose = latest_pose_;
315  pose.header.stamp = e.current_real;
316  publishTF(pose);
317  }
318 
319  std::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
323  std::string object_type_;
324  double object_x_;
325  double object_y_;
326  double object_z_;
327  double object_r_;
328  double object_g_;
329  double object_b_;
330  double object_a_;
331  double line_width_;
333  std::string mesh_file_;
337  std::string tf_frame_;
340  std::shared_ptr<tf::TransformBroadcaster> tf_broadcaster_;
343  geometry_msgs::PoseStamped latest_pose_;
344 };
345 
346 
347 int main(int argc, char** argv) {
348  ros::init(argc, argv, "marker_6dof");
350  ros::spin();
351  return 0;
352 }
ros::Subscriber pose_stamped_sub_
boost::mutex mutex_
interactive_markers::MenuHandler menu_handler_
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
void publishTF(const geometry_msgs::PoseStamped &pose)
double object_a_
bool publish_pose_periodically_
void publish(const boost::shared_ptr< M > &message) const
double object_b_
int initial_x
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double object_g_
void calculateBoundingBox(visualization_msgs::Marker &object_marker)
void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
std::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
interactive_markers::MenuHandler::EntryHandle circle_menu_entry_
top
ROSCPP_DECL const std::string & getName()
void timerPoseCallback(const ros::TimerEvent &e)
void initializeInteractiveMarker()
void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
pose
double object_r_
bool apply(InteractiveMarkerServer &server, const std::string &marker_name)
ROSCPP_DECL void spin(Spinner &spinner)
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
std::shared_ptr< tf::TransformBroadcaster > tf_broadcaster_
bool setCheckState(EntryHandle handle, CheckState check_state)
double object_x_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double object_y_
geometry_msgs::PoseStamped latest_pose_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
std::string object_type_
std::string mesh_file_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool show_6dof_circle_
bool publish_tf_
ros::Timer timer_tf_
mutex_t * lock
void timerTFCallback(const ros::TimerEvent &e)
EntryHandle insert(const std::string &title, const FeedbackCallback &feedback_cb)
ros::Publisher pose_pub_
std::string tf_frame_
int main(int argc, char **argv)
ros::Timer timer_pose_
bool hasParam(const std::string &key) const
double object_z_
double int_marker_scale_
boost::mutex mutex
double line_width_
void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr &msg)


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