PrimitiveCallBase.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * PrimitiveCallBase.hpp
00003  *
00004  *  Created on: May 27, 2015
00005  *      Author: Filip Mandic
00006  *
00007  ********************************************************************/
00008 
00009 /*********************************************************************
00010 * Software License Agreement (BSD License)
00011 *
00012 *  Copyright (c) 2015, LABUST, UNIZG-FER
00013 *  All rights reserved.
00014 *
00015 *  Redistribution and use in source and binary forms, with or without
00016 *  modification, are permitted provided that the following conditions
00017 *  are met:
00018 *
00019 *   * Redistributions of source code must retain the above copyright
00020 *     notice, this list of conditions and the following disclaimer.
00021 *   * Redistributions in binary form must reproduce the above
00022 *     copyright notice, this list of conditions and the following
00023 *     disclaimer in the documentation and/or other materials provided
00024 *     with the distribution.
00025 *   * Neither the name of the LABUST nor the names of its
00026 *     contributors may be used to endorse or promote products derived
00027 *     from this software without specific prior written permission.
00028 *
00029 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00030 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00031 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00032 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00033 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00034 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00035 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00036 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00037 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00038 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00039 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00040 *  POSSIBILITY OF SUCH DAMAGE.
00041 *********************************************************************/
00042 
00043 #ifndef PRIMITIVECALLBASE_HPP_
00044 #define PRIMITIVECALLBASE_HPP_
00045 
00046 #include <ros/ros.h>
00047 #include <actionlib/client/simple_action_client.h>
00048 
00049 #include <std_msgs/String.h>
00050 
00051 namespace labust
00052 {
00053         namespace primitive
00054         {
00058                 template <class ActionType, class ActionGoal, class ActionResult, class ActionFeedback>
00059                 class PrimitiveCallBase
00060                 {
00061                 public:
00062 
00063                         typedef ActionType Action;
00064                         typedef actionlib::SimpleActionClient<Action> ActionClient;
00065                         typedef ActionGoal Goal;
00066                         typedef ActionResult Result;
00067                         typedef ActionFeedback Feedback;
00068 
00069                 protected:
00070 
00074                         PrimitiveCallBase(const std::string& name):primitiveName(name),
00075                                                                                                                   ac(primitiveName.c_str())
00076                         {
00077                                 ros::NodeHandle nh;
00078 
00079                                 /*** Publishers */
00080                                 pubEventString = nh.advertise<std_msgs::String>("eventString",1);
00081 
00082                                 //TODO Throw exception
00083                                 ROS_INFO("Waiting for action server to start.");
00084                                 ac.waitForServer(); //will wait for infinite time
00085                                 ROS_INFO("Action server started, sending goal.");
00086                         }
00087 
00088                         virtual ~PrimitiveCallBase(){}
00089 
00090                 public:
00091                         virtual void start(Goal goal)
00092                         {
00093                                 //LLcfg.LL_VELconfigure(true,2,2,0,0,0,2);
00094                                 this->callPrimitiveAction(goal);
00095                         }
00096 
00097                         virtual void stop()
00098                         {
00099                                 //boost::this_thread::sleep(boost::posix_time::milliseconds(200));
00100                                 ros::Duration(0.2).sleep();
00101                                 ac.cancelGoalsAtAndBeforeTime(ros::Time::now());
00102 
00103                                 //enableController("UALF_enable",false);
00104                                 //enableController("HDG_enable",false);
00105                                 //LLcfg.LL_VELconfigure(false,1,1,0,0,0,1);
00106                         }
00107 
00108                 protected:
00109                         void callPrimitiveAction(Goal goal)
00110                         {
00111                                 ac.sendGoal(goal,
00112                                                         boost::bind(&PrimitiveCallBase::doneCb, this, _1, _2),
00113                                                         boost::bind(&PrimitiveCallBase::activeCb, this),
00114                                                         boost::bind(&PrimitiveCallBase::feedbackCb, this, _1));
00115                         }
00116 
00117 
00118                         // Called once when the goal completes
00119                         virtual void doneCb(const actionlib::SimpleClientGoalState& state, const typename Result::ConstPtr& result)
00120                         {
00121                                 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00122                                 {
00123                                         ROS_ERROR("Finished in state [%s]", state.toString().c_str());
00124                                         publishEventString("/PRIMITIVE_FINISHED");
00125                                 }
00126                         }
00127 
00128                         // Called once when the goal becomes active
00129                         virtual void activeCb()
00130                         {
00131                                 ROS_ERROR("Goal just went active.");
00132                         }
00133 
00134                         // Called every time feedback is received for the goal
00135                         virtual void feedbackCb(const typename Feedback::ConstPtr& feedback)
00136                         {
00137 
00138                         }
00139 
00140                         void publishEventString(std::string event)
00141                         {
00142                                 std_msgs::String msg;
00143                                 msg.data = event.c_str();
00144                                 pubEventString.publish(msg);
00145                         }
00146 
00150                         std::string primitiveName;
00154                         ActionClient ac;
00158                         Action action;
00162                         ros::ServiceClient control_manager;
00166                         ros::Publisher pubEventString;
00167                 };
00168         }
00169 }
00170 
00171 
00172 
00173 #endif /* PRIMITIVECALLBASE_HPP_ */


labust_primitives
Author(s): Filip Mandic
autogenerated on Fri Aug 28 2015 11:22:51