marker_6dof.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015-2016, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include <ros/ros.h>
00037 #include <interactive_markers/interactive_marker_server.h>
00038 #include <interactive_markers/tools.h>
00039 #include <interactive_markers/menu_handler.h>
00040 #include <tf/transform_broadcaster.h>
00041 #include <tf/transform_listener.h>
00042 #include <geometry_msgs/PoseStamped.h>
00043 #include <tf_conversions/tf_eigen.h>
00044 #include <jsk_topic_tools/rosparam_utils.h>
00045 
00046 class Marker6DOF {
00047 public:
00048   Marker6DOF(): show_6dof_circle_(true) {
00049     ros::NodeHandle nh, pnh("~");
00050     pnh.param("publish_tf", publish_tf_, false);
00051     pnh.param("publish_pose_periodically", publish_pose_periodically_, false);
00052     pnh.param("tf_frame", tf_frame_, std::string("object"));
00053     double tf_duration;
00054     pnh.param("tf_duration", tf_duration, 0.1);
00055     pnh.param("object_type", object_type_, std::string("sphere"));
00056     pnh.param("object_x", object_x_, 1.0);
00057     pnh.param("object_y", object_y_, 1.0);
00058     pnh.param("object_z", object_z_, 1.0);
00059     pnh.param("object_r", object_r_, 1.0);
00060     pnh.param("object_g", object_g_, 1.0);
00061     pnh.param("object_b", object_b_, 1.0);
00062     pnh.param("object_a", object_a_, 1.0);
00063     std::string frame_id;
00064     pnh.param("frame_id", frame_id, std::string("/map"));
00065     latest_pose_.header.frame_id = frame_id;
00066     double initial_x, initial_y, initial_z;
00067     pnh.param("initial_x", initial_x, 0.0);
00068     pnh.param("initial_y", initial_y, 0.0);
00069     pnh.param("initial_z", initial_z, 0.0);
00070     latest_pose_.pose.position.x = initial_x;
00071     latest_pose_.pose.position.y = initial_y;
00072     latest_pose_.pose.position.z = initial_z;
00073     std::vector<double> initial_orientation;
00074     if (jsk_topic_tools::readVectorParameter(pnh, "initial_orientation", initial_orientation)) {
00075       latest_pose_.pose.orientation.x = initial_orientation[0];
00076       latest_pose_.pose.orientation.y = initial_orientation[1];
00077       latest_pose_.pose.orientation.z = initial_orientation[2];
00078       latest_pose_.pose.orientation.w = initial_orientation[3];
00079     }
00080     else {
00081       latest_pose_.pose.orientation.w = 1.0;
00082     }
00083     pnh.param("line_width", line_width_, 0.007);
00084     pnh.param("mesh_file", mesh_file_, std::string(""));
00085     if (pnh.hasParam("interactive_marker_scale")) {
00086       pnh.param("interactive_marker_scale", int_marker_scale_, 1.0);
00087     } else {
00088       int_marker_scale_ = std::max(object_x_, std::max(object_y_, object_z_)) + 0.5;
00089     }
00090     if (publish_tf_) {
00091       tf_broadcaster_.reset(new tf::TransformBroadcaster);
00092     }
00093     
00094     pose_pub_ = pnh.advertise<geometry_msgs::PoseStamped>("pose", 1);
00095     pose_stamped_sub_ = pnh.subscribe("move_marker", 1, &Marker6DOF::moveMarkerCB, this);
00096   
00097     circle_menu_entry_
00098       = menu_handler_.insert("Toggle 6DOF Circle",
00099                              boost::bind(&Marker6DOF::menuFeedbackCB, this, _1));
00100     menu_handler_.setCheckState(circle_menu_entry_,
00101                                 interactive_markers::MenuHandler::CHECKED);
00102     server_.reset( new interactive_markers::InteractiveMarkerServer(ros::this_node::getName()));
00103     initializeInteractiveMarker();
00104     // Timer to update current pose on Rviz in the case which user re-enabled the plugin
00105     timer_pose_ = nh.createTimer(ros::Duration(0.1), boost::bind(&Marker6DOF::timerPoseCallback, this, _1));
00106     if (publish_tf_) {
00107       timer_tf_ = nh.createTimer(ros::Duration(tf_duration), boost::bind(&Marker6DOF::timerTFCallback, this, _1));
00108     }
00109   }
00110   
00111 protected:
00112   void moveMarkerCB(const geometry_msgs::PoseStamped::ConstPtr& msg) {
00113     boost::mutex::scoped_lock lock(mutex_);
00114     if(!publish_pose_periodically_) {
00115       pose_pub_.publish(msg);
00116     }
00117     server_->setPose("marker", msg->pose, msg->header);
00118     latest_pose_ = geometry_msgs::PoseStamped(*msg);
00119     server_->applyChanges();
00120   }
00121 
00122   
00123   void calculateBoundingBox( visualization_msgs::Marker& object_marker){
00124     geometry_msgs::Point top[5];
00125     top[0].x = object_x_/2;
00126     top[0].y = object_y_/2;
00127     top[1].x = -object_x_/2;
00128     top[1].y = object_y_/2;
00129     top[2].x = -object_x_/2;
00130     top[2].y = -object_y_/2;
00131     top[3].x = object_x_/2;
00132     top[3].y = -object_y_/2;    
00133     top[4].x = object_x_/2;
00134     top[4].y = object_y_/2;
00135 
00136     geometry_msgs::Point bottom[5];
00137     bottom[0].x = object_x_/2;
00138     bottom[0].y = object_y_/2;
00139     bottom[1].x = -object_x_/2;
00140     bottom[1].y = object_y_/2;
00141     bottom[2].x = -object_x_/2;
00142     bottom[2].y = -object_y_/2;
00143     bottom[3].x = object_x_/2;
00144     bottom[3].y = -object_y_/2;
00145     bottom[4].x = object_x_/2;
00146     bottom[4].y = object_y_/2;
00147 
00148     for(int i = 0; i< 5; i++){
00149       top[i].z = object_z_/2;
00150       bottom[i].z = -object_z_/2;
00151     }
00152 
00153     for(int i = 0; i< 4; i++){
00154       object_marker.points.push_back(top[i]);
00155       object_marker.points.push_back(top[i+1]);
00156       object_marker.points.push_back(bottom[i]);
00157       object_marker.points.push_back(bottom[i+1]);
00158       object_marker.points.push_back(top[i]);
00159       object_marker.points.push_back(bottom[i]);
00160     }
00161   }
00162   
00163   void initializeInteractiveMarker() {
00164     visualization_msgs::InteractiveMarker int_marker;
00165     int_marker.header.frame_id = latest_pose_.header.frame_id;
00166     int_marker.name = "marker";
00167     int_marker.pose = geometry_msgs::Pose(latest_pose_.pose);
00168     
00169     visualization_msgs::Marker object_marker;
00170     if(object_type_ == std::string("cube")){
00171       object_marker.type = visualization_msgs::Marker::CUBE;
00172       object_marker.scale.x = object_x_;
00173       object_marker.scale.y = object_y_;
00174       object_marker.scale.z = object_z_;
00175       object_marker.color.r = object_r_;
00176       object_marker.color.g = object_g_;
00177       object_marker.color.b = object_b_;
00178       object_marker.color.a = object_a_;
00179       object_marker.pose.orientation.w = 1.0;
00180     }
00181     else if( object_type_ == std::string("sphere") ){
00182       object_marker.type = visualization_msgs::Marker::SPHERE;
00183       object_marker.scale.x = object_x_;
00184       object_marker.scale.y = object_y_;
00185       object_marker.scale.z = object_z_;
00186       object_marker.color.r = object_r_;
00187       object_marker.color.g = object_g_;
00188       object_marker.color.b = object_b_;
00189       object_marker.color.a = object_a_;
00190       object_marker.pose.orientation.w = 1.0;
00191     }
00192     else if(object_type_ == std::string("line")){
00193       object_marker.type = visualization_msgs::Marker::LINE_LIST;
00194       object_marker.scale.x = line_width_;
00195       object_marker.color.r = object_r_;
00196       object_marker.color.g = object_g_;
00197       object_marker.color.b = object_b_;
00198       object_marker.color.a = object_a_;
00199       object_marker.pose.orientation.w = 1.0;
00200       calculateBoundingBox(object_marker);
00201     }
00202     else if(object_type_ == std::string("mesh")){
00203       object_marker.type = visualization_msgs::Marker::MESH_RESOURCE;
00204       object_marker.scale.x = object_x_;
00205       object_marker.scale.y = object_y_;
00206       object_marker.scale.z = object_z_;
00207       object_marker.color.r = object_r_;
00208       object_marker.color.g = object_g_;
00209       object_marker.color.b = object_b_;
00210       object_marker.color.a = object_a_;
00211       object_marker.pose.orientation.w = 1.0;
00212       object_marker.mesh_resource = mesh_file_;
00213     }
00214 
00215     
00216     visualization_msgs::InteractiveMarkerControl object_marker_control;
00217     object_marker_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::BUTTON;
00218     object_marker_control.always_visible = true;
00219     object_marker_control.markers.push_back(object_marker);
00220     int_marker.controls.push_back(object_marker_control);
00221   
00222     visualization_msgs::InteractiveMarkerControl control;
00223     if (show_6dof_circle_) {
00224       control.orientation.w = 1;
00225       control.orientation.x = 1;
00226       control.orientation.y = 0;
00227       control.orientation.z = 0;
00228     
00229       control.name = "rotate_x";
00230       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00231       int_marker.controls.push_back(control);
00232       control.name = "move_x";
00233       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00234       int_marker.controls.push_back(control);
00235 
00236       control.orientation.w = 1;
00237       control.orientation.x = 0;
00238       control.orientation.y = 1;
00239       control.orientation.z = 0;
00240       control.name = "rotate_z";
00241       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00242       int_marker.controls.push_back(control);
00243       control.name = "move_z";
00244       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00245       int_marker.controls.push_back(control);
00246 
00247       control.orientation.w = 1;
00248       control.orientation.x = 0;
00249       control.orientation.y = 0;
00250       control.orientation.z = 1;
00251       control.name = "rotate_y";
00252       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
00253       int_marker.controls.push_back(control);
00254       control.name = "move_y";
00255       control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
00256       int_marker.controls.push_back(control);
00257     }
00258   
00259     int_marker.scale = int_marker_scale_;
00260 
00261     server_->insert(int_marker,
00262                     boost::bind(&Marker6DOF::processFeedbackCB, this, _1));
00263     
00264     menu_handler_.apply(*server_, "marker");
00265     server_->applyChanges();
00266   }
00267 
00268   void publishTF(const geometry_msgs::PoseStamped& pose) {
00269     tf::Transform transform;
00270     tf::poseMsgToTF(pose.pose, transform);
00271     tf_broadcaster_->sendTransform(tf::StampedTransform(
00272                                      transform, pose.header.stamp,
00273                                      pose.header.frame_id,
00274                                      tf_frame_));
00275   }
00276   
00277   void processFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00278     boost::mutex::scoped_lock lock(mutex_);
00279     geometry_msgs::PoseStamped pose;
00280     pose.header = feedback->header;
00281     pose.pose = feedback->pose;
00282     latest_pose_ = pose;
00283     if (!publish_pose_periodically_) {
00284       pose_pub_.publish(pose);
00285     }
00286   }
00287 
00288   void menuFeedbackCB(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) {
00289     show_6dof_circle_ = !show_6dof_circle_;
00290     if (show_6dof_circle_) {
00291       menu_handler_.setCheckState(circle_menu_entry_,
00292                                   interactive_markers::MenuHandler::CHECKED);
00293     }
00294     else {
00295       menu_handler_.setCheckState(circle_menu_entry_,
00296                                   interactive_markers::MenuHandler::UNCHECKED);
00297     }
00298     initializeInteractiveMarker(); // ok...?
00299   }
00300 
00301   void timerPoseCallback(const ros::TimerEvent& e) {
00302     boost::mutex::scoped_lock lock(mutex_);
00303     geometry_msgs::PoseStamped pose = latest_pose_;
00304     pose.header.stamp = e.current_real;
00305     server_->setPose("marker", pose.pose, pose.header);
00306     server_->applyChanges();
00307     if (publish_pose_periodically_) {
00308       pose_pub_.publish(pose);
00309     }
00310   }
00311 
00312   void timerTFCallback(const ros::TimerEvent& e) {
00313     boost::mutex::scoped_lock lock(mutex_);
00314     geometry_msgs::PoseStamped pose = latest_pose_;
00315     pose.header.stamp = e.current_real;
00316     publishTF(pose);
00317   }
00318 
00319   std::shared_ptr<interactive_markers::InteractiveMarkerServer> server_;
00320   interactive_markers::MenuHandler menu_handler_;
00321   ros::Subscriber pose_stamped_sub_;
00322   ros::Publisher pose_pub_;
00323   std::string object_type_;
00324   double object_x_;
00325   double object_y_;
00326   double object_z_;
00327   double object_r_;
00328   double object_g_;
00329   double object_b_;
00330   double object_a_;
00331   double line_width_;
00332   double int_marker_scale_;
00333   std::string mesh_file_;
00334   bool show_6dof_circle_;
00335   bool publish_tf_;
00336   bool publish_pose_periodically_;
00337   std::string tf_frame_;
00338   ros::Timer timer_pose_;
00339   ros::Timer timer_tf_;
00340   std::shared_ptr<tf::TransformBroadcaster> tf_broadcaster_;
00341   boost::mutex mutex_;
00342   interactive_markers::MenuHandler::EntryHandle circle_menu_entry_;
00343   geometry_msgs::PoseStamped latest_pose_;
00344 };
00345 
00346 
00347 int main(int argc, char** argv) {
00348   ros::init(argc, argv, "marker_6dof");
00349   Marker6DOF marker;
00350   ros::spin();
00351   return 0;
00352 }


jsk_interactive_marker
Author(s): furuta
autogenerated on Wed May 1 2019 02:40:31