pr2_gripper_sensor_controller.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *  \author Joe Romano
00036  *********************************************************************/
00037 //@author  Joe Romano
00038 //@email   joeromano@gmail.com
00039 //@brief   pr2_gripper_sensor_controller.cpp  - controller to read data from
00040 //         the sensors on the pr2 gripper (accelerometer in palm,
00041 //         pressure arrays on the fingers, and encoder in the hand) 
00042 //         and publish higher-level useful processed information about
00043 //         them, as well as perform low-level control tasks to control
00044 //         the gripper based on these signals in real-time.
00045 //         
00046 //         This controller is inteded to be interacted with through its
00047 //         action interface, pr2_gripper_sensor_action.
00048 
00049 #include <pr2_controller_interface/controller.h>
00050 #include <pr2_gripper_sensor_controller/gripper_controller.h>
00051 #include <pr2_gripper_sensor_controller/pressure_observer.h>
00052 #include <pr2_gripper_sensor_controller/acceleration_observer.h>
00053 #include <pr2_hardware_interface/hardware_interface.h>
00054 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactData.h>
00055 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactCommand.h>
00056 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoData.h>
00057 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoCommand.h>
00058 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoData.h>
00059 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand.h>
00060 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorData.h>
00061 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand.h>
00062 #include <pr2_gripper_sensor_msgs/PR2GripperSensorRTState.h>
00063 #include <pr2_gripper_sensor_msgs/PR2GripperSensorRawData.h>
00064 #include <std_srvs/Empty.h>
00065 #include <std_msgs/Empty.h>
00066 
00067 #include <ros/ros.h>
00068 
00069 #include <pr2_controllers_msgs/JointControllerState.h>
00070 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
00071 #include <boost/scoped_ptr.hpp>
00072 #include <boost/thread/condition.hpp>
00073 #include <realtime_tools/realtime_box.h>
00074 #include <realtime_tools/realtime_publisher.h>
00075 #include <std_msgs/Float64.h>
00076 
00077 
00078 namespace pr2_gripper_sensor_controller{
00079 
00080 class PR2GripperSensorController: public pr2_controller_interface::Controller
00081 {
00082 private:
00083   ros::NodeHandle nodeHandle;                   
00084   pr2_mechanism_model::RobotState *robotHandle; 
00085 
00086 
00087   // functions ---------------
00088   bool initializeHandles(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00089   bool forceServo();
00090   bool updateZeros(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
00091   bool stopMotorOutput(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
00092   void reinitializeValues();
00093   bool reloadParams(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
00094   
00095   // variables ---------------
00096   int loop_count_;         
00097   int contactCounter;      
00098   bool stable_contact;     
00099   bool placedState;        
00100   bool update_zeros;       
00101   int placeConditions;     
00102   double acc_trigger;      
00103   double slip_trigger;     
00104   bool stable_force;       
00105   int findContact_delay;   
00106   int publish_skip;            
00107 
00108   // state variables about our controller
00109   int control_mode;        
00110   bool contact_success;    
00111   double servo_force;      
00112   double servo_position;   
00113   double max_effort;       
00114   double servo_velocity;   
00115   int contacts_desired;   
00116   double deformation_limit;
00117   double fingertip_start_force; 
00118   double fingertip_force_limit; 
00119   double force_servo_velocity_tolerance; 
00120   const pr2_gripper_sensor_msgs::PR2GripperSensorRTState rt_state_def; 
00121   pr2_gripper_sensor_msgs::PR2GripperSensorRawData raw_data;
00122   bool publish_raw_data;   
00123 
00124   ros::Time last_time_;    
00125 
00126   accelerationObserver *myAccelerationObserver;   
00127   gripperController *myGripperController;         
00128   pressureObserver *myPressureObserver;           
00129 
00130   
00132   ros::ServiceServer updateZeros_srv_;
00133   ros::ServiceServer reloadParams_srv_;
00134   ros::ServiceServer stopMotorOutput_srv_;
00135 
00137   std_srvs::Empty::Request empty_req;
00138   std_srvs::Empty::Response empty_resp;
00139 
00140 
00142   boost::scoped_ptr<
00143     realtime_tools::RealtimePublisher<
00144     pr2_gripper_sensor_msgs::PR2GripperSensorRawData> > raw_data_publisher_ ;
00145 
00147   boost::scoped_ptr<
00148     realtime_tools::RealtimePublisher<
00149     pr2_controllers_msgs::JointControllerState> > controller_state_publisher_ ;
00150   ros::Subscriber sub_command_;
00151   void positionCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr& msg);
00152 
00154   boost::scoped_ptr<
00155     realtime_tools::RealtimePublisher<
00156     pr2_gripper_sensor_msgs::PR2GripperFindContactData> > contact_state_publisher_ ;
00157   ros::Subscriber sub_findcontact_command_;
00158   void findContactCB(const pr2_gripper_sensor_msgs::PR2GripperFindContactCommandConstPtr& msg);
00159 
00161   boost::scoped_ptr<
00162     realtime_tools::RealtimePublisher<
00163     pr2_gripper_sensor_msgs::PR2GripperSlipServoData> > slip_state_publisher_ ;
00164   ros::Subscriber sub_slipservo_command_;
00165   void slipServoCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoCommandConstPtr& msg);
00166 
00168   boost::scoped_ptr<
00169     realtime_tools::RealtimePublisher<
00170     pr2_gripper_sensor_msgs::PR2GripperForceServoData> > force_state_publisher_ ;
00171   ros::Subscriber sub_forceservo_command_;
00172   void forceServoCB(const pr2_gripper_sensor_msgs::PR2GripperForceServoCommandConstPtr& msg);
00173 
00175   boost::scoped_ptr<
00176     realtime_tools::RealtimePublisher<
00177     pr2_gripper_sensor_msgs::PR2GripperEventDetectorData> > event_detector_state_publisher_ ;
00178   ros::Subscriber sub_event_detector_command_;
00179   void eventDetectorCB(const pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommandConstPtr& msg);
00180   
00181 public:
00182   virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00183   virtual void update();
00184   virtual void stopping();
00185   virtual void starting() {}
00186 
00187 };
00188 } 


pr2_gripper_sensor_controller
Author(s): Joe Romano
autogenerated on Thu Jun 6 2019 18:02:06