checkout_controller.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Author: Kevin Watts
00036 
00037 #ifndef _JOINT_QUALIFICATION_CONTROLLERS_CHECKOUT_CONTROLLER_H_
00038 #define _JOINT_QUALIFICATION_CONTROLLERS_CHECKOUT_CONTROLLER_H_
00039 
00040 /***************************************************/
00049 /***************************************************/
00050 
00051 #include "ros/ros.h"
00052 #include <string>
00053 #include <math.h>
00054 #include <boost/scoped_ptr.hpp>
00055 #include "joint_qualification_controllers/RobotData.h"
00056 #include "realtime_tools/realtime_publisher.h"
00057 #include "pr2_controller_interface/controller.h"
00058 
00059 
00060 namespace joint_qualification_controllers
00061 {
00062 
00063 
00064 /***************************************************/
00071 /***************************************************/
00072 
00073 class CheckoutController : public pr2_controller_interface::Controller
00074 {
00075 
00076 public:
00077   enum { STARTING, LISTENING, ANALYZING, DONE};
00078 
00079   CheckoutController();
00080   ~CheckoutController() { }
00081 
00087   bool init( pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00088 
00092   void starting();
00093   
00097   void update();
00098 
00102   bool sendData();
00103 
00107   void analysis(double time, bool timeout = false);
00108 
00109 
00110 private:
00111   pr2_mechanism_model::RobotState *robot_;   
00112   ros::Time initial_time_;  
00114   double timeout_;
00115 
00116   joint_qualification_controllers::RobotData robot_data_;
00117   
00118   int state_;
00119 
00120   int joint_count_;
00121   int actuator_count_;
00122 
00123   bool done() { return state_ == DONE; }
00124 
00125   bool data_sent_;
00126 
00127   double last_publish_time_;
00128 
00129   // RT service call
00130   boost::scoped_ptr<realtime_tools::RealtimePublisher<
00131                       joint_qualification_controllers::RobotData> > robot_data_pub_;
00132 };
00133 
00134 
00135 
00136 }
00137 
00138 
00139 #endif //  _JOINT_QUALIFICATION_CONTROLLERS_CHECKOUT_CONTROLLER_H_


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Mon Sep 14 2015 14:38:58