$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00040 #include <interactive_markers/interactive_marker_server.h> 00041 #include <geometry_msgs/Pose.h> 00042 #include <ros/ros.h> 00043 #include <boost/optional.hpp> 00044 #include <boost/thread.hpp> 00045 #include <boost/lexical_cast.hpp> 00046 #include <tf/transform_broadcaster.h> 00047 00048 namespace flirtlib_ros 00049 { 00050 00051 namespace gm=geometry_msgs; 00052 namespace im=interactive_markers; 00053 namespace vm=visualization_msgs; 00054 00055 using std::vector; 00056 using std::string; 00057 using boost::bind; 00058 using boost::optional; 00059 00060 typedef boost::mutex::scoped_lock Lock; 00061 00062 00063 /************************************************************ 00064 * Node class 00065 ***********************************************************/ 00066 00067 class MarkerNode 00068 { 00069 public: 00070 00071 MarkerNode (); 00072 void publishPoses (const ros::TimerEvent& e); 00073 void handlePoseUpdate (const unsigned id, const vm::InteractiveMarkerFeedback::ConstPtr& f); 00074 00075 private: 00076 00077 ros::NodeHandle nh_; 00078 const double pub_rate_; 00079 const double num_markers_; 00080 00081 vector<gm::Pose> poses_; 00082 00083 boost::mutex mutex_; 00084 ros::Timer pub_timer_; 00085 tf::TransformBroadcaster tfb_; 00086 im::InteractiveMarkerServer im_server_; 00087 }; 00088 00089 /************************************************************ 00090 * Functions 00091 ***********************************************************/ 00092 00093 template <typename T> 00094 T getParam (const string& name, const T& default_val) 00095 { 00096 T val; 00097 ros::NodeHandle nh("~"); 00098 nh.param(name, val, default_val); 00099 ROS_INFO_STREAM ("Setting " << name << " to " << val); 00100 return val; 00101 } 00102 00103 ros::Duration duration (const double r) 00104 { 00105 return ros::Duration(r==0.0 ? 0.0 : 1/r); 00106 } 00107 00108 00109 MarkerNode::MarkerNode () : 00110 pub_rate_(getParam<double>("pub_rate", 10.0)), 00111 num_markers_(getParam<int>("num_markers", 2)), 00112 pub_timer_(nh_.createTimer(duration(pub_rate_), 00113 &MarkerNode::publishPoses, this)), 00114 im_server_("int_markers", "", false) 00115 { 00116 poses_.resize(num_markers_); 00117 for (unsigned i=0; i<num_markers_; i++) 00118 { 00119 // Set up an interactive marker that allows moving marker in 2d 00120 vm::InteractiveMarker int_marker; 00121 int_marker.header.frame_id = "/map"; 00122 int_marker.scale = 0.5; 00123 int_marker.pose.position.y = 25.0+2.0*i; 00124 int_marker.pose.position.x = 15.0; 00125 int_marker.pose.orientation.w = 1.0; 00126 poses_[i] = int_marker.pose; 00127 00128 int_marker.name = string("marker") + boost::lexical_cast<string>(i); 00129 00130 vm::Marker marker; 00131 marker.type = vm::Marker::ARROW; 00132 marker.scale.x = 2.0; 00133 marker.scale.y = 2.0; 00134 marker.scale.z = 1.0; 00135 marker.color.r = 0.5; 00136 marker.color.b = 0.5; 00137 marker.color.a = 1.0; 00138 00139 vm::InteractiveMarkerControl control; 00140 control.orientation.w = 1.0; 00141 control.orientation.y = 1.0; 00142 control.interaction_mode = vm::InteractiveMarkerControl::MOVE_ROTATE; 00143 control.always_visible = true; 00144 control.markers.push_back(marker); 00145 int_marker.controls.push_back(control); 00146 00147 im_server_.insert(int_marker); 00148 im_server_.setCallback(int_marker.name, 00149 bind(&MarkerNode::handlePoseUpdate, 00150 this, i, _1), 00151 vm::InteractiveMarkerFeedback::POSE_UPDATE); 00152 00153 00154 } 00155 im_server_.applyChanges(); 00156 ROS_INFO ("Initialized"); 00157 } 00158 00159 00160 tf::StampedTransform toTf (const gm::Pose& p, const string& frame) 00161 { 00162 tf::Transform trans; 00163 const gm::Point pos=p.position; 00164 const gm::Quaternion rot=p.orientation; 00165 trans.setOrigin(btVector3(pos.x, pos.y, pos.z)); 00166 trans.setRotation(btQuaternion(rot.x, rot.y, rot.z, rot.w)); 00167 return tf::StampedTransform(trans, ros::Time::now(), "/map", frame); 00168 } 00169 00170 void MarkerNode::publishPoses (const ros::TimerEvent& e) 00171 { 00172 Lock l(mutex_); 00173 if (poses_.size()>=num_markers_) 00174 { 00175 for (unsigned i=0; i<num_markers_; i++) 00176 { 00177 const string frame = "pose" + boost::lexical_cast<string>(i); 00178 tfb_.sendTransform(toTf(poses_[i], frame)); 00179 } 00180 } 00181 else 00182 ROS_INFO_THROTTLE(2.0, "Waiting for marker poses before publishing"); 00183 } 00184 00185 void MarkerNode::handlePoseUpdate 00186 (const unsigned i, 00187 const vm::InteractiveMarkerFeedback::ConstPtr& f) 00188 { 00189 Lock l(mutex_); 00190 ROS_DEBUG_STREAM_NAMED ("update", "Received update for marker " << i << 00191 "; pose is now " << f->pose); 00192 poses_[i] = f->pose; 00193 } 00194 00195 00196 00197 00198 } // namespace 00199 00200 00201 int main (int argc, char** argv) 00202 { 00203 ros::init(argc, argv, "interactive_markers"); 00204 flirtlib_ros::MarkerNode node; 00205 ros::spin(); 00206 return 0; 00207 }