marker_server.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, 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 #include <ros/ros.h>
00031 #include <interactive_markers/interactive_marker_server.h>
00032 #include <string.h>
00033 #include <geometry_msgs/Twist.h>
00034 #include <geometry_msgs/Pose.h>
00035 #include <tf/tf.h>
00036 
00037 using namespace visualization_msgs;
00038 
00039 class MarkerServer
00040 {
00041   public:
00042     MarkerServer()
00043       : nh("~"), server("twist_marker_server")
00044     {
00045       std::string cmd_vel_topic;
00046 
00047       nh.param<std::string>("link_name", link_name, "/base_link");
00048       nh.param<std::string>("robot_name", robot_name, "robot");
00049       nh.param<double>("linear_scale", linear_drive_scale, 1.0);
00050       nh.param<double>("angular_scale", angular_drive_scale, 2.2);
00051       nh.param<double>("marker_size_scale", marker_size_scale, 1.0);
00052 
00053       vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel", 1);
00054       createInteractiveMarkers();
00055 
00056       ROS_INFO("[twist_marker_server] Initialized.");
00057     }
00058 
00059     void processFeedback(
00060         const InteractiveMarkerFeedbackConstPtr &feedback );
00061   
00062   private:
00063     void createInteractiveMarkers();
00064   
00065     ros::NodeHandle nh;
00066     ros::Publisher vel_pub;
00067     interactive_markers::InteractiveMarkerServer server;
00068     
00069     double linear_drive_scale;
00070     double angular_drive_scale;
00071 
00072     double marker_size_scale;
00073     
00074     std::string link_name;
00075     std::string robot_name;
00076 };
00077 
00078 void MarkerServer::processFeedback(
00079     const InteractiveMarkerFeedbackConstPtr &feedback )
00080 {
00081   // Handle angular change (yaw is the only direction in which you can rotate)
00082   double yaw = tf::getYaw(feedback->pose.orientation);
00083   
00084   geometry_msgs::Twist vel;
00085   vel.angular.z = angular_drive_scale * yaw;
00086   vel.linear.x = linear_drive_scale * feedback->pose.position.x;
00087 
00088   vel_pub.publish(vel);    
00089   
00090   // Make the marker snap back to robot
00091   server.setPose(robot_name + "_twist_marker", geometry_msgs::Pose());
00092   
00093   server.applyChanges();
00094 }
00095 
00096 void MarkerServer::createInteractiveMarkers()
00097 { 
00098   // create an interactive marker for our server
00099   InteractiveMarker int_marker;
00100   int_marker.header.frame_id = link_name;
00101   int_marker.name = robot_name + "_twist_marker";
00102   int_marker.description = "twist controller for " + robot_name;
00103   int_marker.scale = marker_size_scale;
00104   
00105   InteractiveMarkerControl control;
00106 
00107   control.orientation_mode = InteractiveMarkerControl::FIXED;
00108   control.orientation.w = 1;
00109   control.orientation.x = 1;
00110   control.orientation.y = 0;
00111   control.orientation.z = 0;
00112   control.name = "move_x";
00113   control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00114   int_marker.controls.push_back(control);
00115 
00116   control.orientation.w = 1;
00117   control.orientation.x = 0;
00118   control.orientation.y = 1;
00119   control.orientation.z = 0;
00120   control.name = "rotate_z";
00121   
00122   control.interaction_mode = InteractiveMarkerControl::MOVE_ROTATE;
00123   //control.interaction_mode = InteractiveMarkerControl::ROTATE_AXIS;
00124   int_marker.controls.push_back(control);
00125 
00126   // Commented out for non-holonomic robot. If holonomic, can move in y.
00127   /*control.orientation.w = 1;
00128   control.orientation.x = 0;
00129   control.orientation.y = 0;
00130   control.orientation.z = 1;
00131   control.name = "move_y";
00132   control.interaction_mode = InteractiveMarkerControl::MOVE_AXIS;
00133   int_marker.controls.push_back(control);*/
00134   
00135   server.insert(int_marker, boost::bind( &MarkerServer::processFeedback, this, _1 ));
00136   
00137   server.applyChanges();
00138 }
00139 
00140 
00141 int main(int argc, char** argv)
00142 {
00143   ros::init(argc, argv, "marker_server");
00144   MarkerServer server;
00145   
00146   ros::spin();
00147 }


interactive_marker_twist_server
Author(s):
autogenerated on Wed Aug 26 2015 12:00:24