rotate_in_place.cpp
Go to the documentation of this file.
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 
00039 #include <flirtlib_ros/RotateInPlaceAction.h>
00040 #include <actionlib/server/simple_action_server.h>
00041 #include <ros/ros.h>
00042 #include <tf/transform_listener.h>
00043 #include <tf/transform_datatypes.h>
00044 #include <control_toolbox/pid.h>
00045 
00046 namespace flirtlib_ros
00047 {
00048 
00049 namespace gm=geometry_msgs;
00050 using std::string;
00051 
00052 /************************************************************
00053  * Class def
00054  ***********************************************************/
00055 
00056 class RotateInPlace
00057 {
00058 public:
00059   
00060   RotateInPlace();
00061   
00062 private:
00063 
00064   control_toolbox::Pid pid_;
00065 
00066   ros::NodeHandle nh_, private_nh_;
00067   tf::TransformListener tf_;
00068   actionlib::SimpleActionServer<RotateInPlaceAction> as_;
00069   ros::Publisher vel_pub_;
00070 
00071   void execute (const RotateInPlaceGoal::ConstPtr& goal);
00072   double currentOrientation (const string& frame_id);
00073 };
00074 
00075 
00076 /************************************************************
00077  * Constructor
00078  ***********************************************************/
00079 
00080 RotateInPlace::RotateInPlace () :
00081   private_nh_("~"),
00082   as_(nh_, "rotate_in_place", boost::bind(&RotateInPlace::execute, this, _1)),
00083   vel_pub_(nh_.advertise<gm::Twist>("navigation/cmd_vel", 1))
00084 {
00085   pid_.init(private_nh_);
00086   double p, i, d, i_min, i_max;
00087   pid_.getGains(p, i, d, i_max, i_min);
00088   ROS_DEBUG_NAMED ("rotate_client", "Rotate action client started: (%.2f, %.2f, %.2f, %.2f, %.2f)",
00089                    p, i, d, i_min, i_max);
00090 }
00091 
00092 
00093 /************************************************************
00094  * Action server
00095  ***********************************************************/
00096 
00097 double RotateInPlace::currentOrientation (const string& frame_id) 
00098 {
00099   tf::StampedTransform trans;
00100   tf_.lookupTransform(frame_id, "base_footprint", ros::Time(), trans);
00101   return tf::getYaw(trans.getRotation());
00102 }
00103 
00104 void RotateInPlace::execute (const RotateInPlaceGoal::ConstPtr& goal)
00105 {
00106   ROS_DEBUG_STREAM_NAMED ("rotate_client", "In the execute callback with goal " << *goal);
00107   RotateInPlaceResult result;
00108   ros::Duration d(0.1);
00109   pid_.updatePid(0, d); // for stability
00110   
00111   ROS_DEBUG_STREAM_NAMED ("rotate_client", "Waiting for transform");
00112   tf_.waitForTransform(goal->header.frame_id, "base_footprint", ros::Time::now(), ros::Duration(2.0));
00113   ROS_DEBUG_STREAM_NAMED ("rotate_client", "Found");
00114   
00115   while (ros::ok()) {
00116     const double current = currentOrientation(goal->header.frame_id);
00117     if (fabs(current-goal->target) < goal->tol) {
00118       result.achieved = current;
00119       break;
00120     }
00121     if (as_.isPreemptRequested()) 
00122     {
00123       result.achieved = current;
00124       as_.setPreempted();
00125       return;
00126     }
00127     gm::Twist vel;
00128     vel.angular.z = pid_.updatePid(current-goal->target, d);
00129     ROS_DEBUG_STREAM_THROTTLE_NAMED (1, "rotate_loop", "Current yaw is " << current << "; desired is " <<
00130                                      goal->target << "; pid effort is " << vel.angular.z);
00131     vel_pub_.publish(vel);
00132     d.sleep();
00133   }
00134   
00135   as_.setSucceeded(result);
00136 }
00137 
00138 
00139 } // namespace flirtlib_ros
00140 
00141 
00142 
00143 int main (int argc, char** argv)
00144 {
00145   ros::init(argc, argv, "rotate_in_place");
00146   flirtlib_ros::RotateInPlace node;
00147   ros::spin();
00148   return 0;
00149 }


flirtlib_ros
Author(s): Bhaskara Marthi
autogenerated on Thu Nov 28 2013 11:21:50