pressure_observer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * \author Joe Romano
36  *********************************************************************/
37 //@author Joe Romano
38 //@email joeromano@gmail.com
39 //@brief pressure_observer.h
40 
42 #include <pr2_gripper_sensor_msgs/PR2GripperPressureData.h>
44 
45 #ifndef _PRESSURE_OBSERVER
46 #define _PRESSURE_OBSERVER
47 
48 #define UNITS_PER_N 1600
49 
51 
52  public:
53  // functions
55  ~pressureObserver(); // default destructor
56  void spin(); // method to update sensor data. should run at 1khz
57  bool graspContact(int contactsDesired); // detects finger impacts
58  void updateZeros2(); // method to update our zero value offsets (zero_offset)
59  bool checkPlaceContact(double dF); // method to look for impact slip and return true
60  bool checkSlip(double slip_motion_limit = 0.007, double slip_force_limit = 0.18);
61  int checkSideImpact(double dF); // method to check for side impacts on finger sensors
63 
64 
65  double padForce_cur; // fingerpad force average between both fingers
66  double padForce_cur_nonbiased; // force average from the non-biased pressures
67  double padForce_left_cur, padForce_left_prev; // current cumulative force on our left/rigth fingerpads
69  double padForce_right_cur, padForce_right_prev; // previous cumulative force on our left/right fingerpads
71  double totalLoading_left, totalLoading_right; // total dynamic laoding on our left/right pads
72  double totalLoading,totalLoading_prev; // left and right loading average
73  double cellLoading_left, cellLoading_right; // cellular loading on the left/right fingers
74  double forceLightest;
77  bool broken_sensor; // flag to indicate we may have a broken sensor
78  bool left_contact, right_contact; // flags to indicate whether a left or right contact happened
80 
81  // storage of our pressure sensor state information. _now is the most recent raw data. _prev is the last subsampled value
82  // _current is the current subsampled value
83  pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_now, pressure_prev, pressure_current;
84  pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_now, pressure_thresh_prev, pressure_thresh_current;
85  pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_zerod, pressure_current_zerod;
86  pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_bias, pressure_cur_bias;
87  pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_bp;
88 
91 
92 
93  private:
94  void getPadCentroid(boost::array<double,22> pressureArray, double *x, double *y);
95  void updateXYCentroids();
96  bool updatePressureState(); // method to acquire new data from both fingers and apply appropriate subsampling
97  void updateTotalLoading(); // method to update the toal loading of each finger totalLoad_left _right
98  void zero(); // method to zero out data
99  void bias_estimator(); // remove mean bias for near zero data
100  double getPadForce(boost::array<double,22> pressureArray); // translate fingertip pressure vector to cumultive sum on the fingerpad (just the pad)
101  void updateContactState(); // update the state of the robots contact sensors
102 
103 
104  pr2_hardware_interface::PressureSensor* left_finger;// a copy of our pressure sensor handle
105  pr2_hardware_interface::PressureSensor* right_finger;// a copy of our pressure sensor handle
106 
107  int subSample_cnt; // a counter to keep track of how many samples we ignored during subsampling
108  int subSample_steps; // 1+ the number of values to skip during subsampling
109  int zero_samples; // the number of samples to use when trying to evaluate our zero offset
110  int zero_cnt; // counter to keep track of how many samples we've stored for zero estimation
111  pr2_gripper_sensor_msgs::PR2GripperPressureData zero_offset;// a storage container for our zero offset values
112 
113  double time_prev, time_cur; // stroage containers for the previous and current pressure update times
114  double dt; // the time expired between pressure update iterations
115 
116 };
117 
118 
119 
120 #endif // _PRESSURE_OBSERVER
pressureObserver::pressure_prev_zerod
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_zerod
Definition: pressure_observer.h:85
pressureObserver::dt
double dt
Definition: pressure_observer.h:114
pressureObserver::cellLoading_right
double cellLoading_right
Definition: pressure_observer.h:73
pressureObserver::getPadForce
double getPadForce(boost::array< double, 22 > pressureArray)
Definition: pressure_observer.cpp:190
pressureObserver::padForce_cur_nonbiased
double padForce_cur_nonbiased
Definition: pressure_observer.h:66
pressureObserver::pressure_thresh_current
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_current
Definition: pressure_observer.h:84
pressureObserver::pressureObserver
pressureObserver(pr2_hardware_interface::PressureSensor *left, pr2_hardware_interface::PressureSensor *right)
Definition: pressure_observer.cpp:329
pressureObserver::padForce_right_cur_nonbiased
double padForce_right_cur_nonbiased
Definition: pressure_observer.h:70
pressureObserver::checkSideImpact
int checkSideImpact(double dF)
Definition: pressure_observer.cpp:113
pressureObserver::zero_offset
pr2_gripper_sensor_msgs::PR2GripperPressureData zero_offset
Definition: pressure_observer.h:111
pressureObserver::pressure_now
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_now
Definition: pressure_observer.h:83
pressureObserver::getPadCentroid
void getPadCentroid(boost::array< double, 22 > pressureArray, double *x, double *y)
Definition: pressure_observer.cpp:284
pressureObserver::padForce_cur
double padForce_cur
Definition: pressure_observer.h:65
pressureObserver::pressure_current_zerod
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_current_zerod
Definition: pressure_observer.h:85
pressureObserver::time_cur
double time_cur
Definition: pressure_observer.h:113
pressureObserver::updateBrokenSensorStatus
void updateBrokenSensorStatus()
Definition: pressure_observer.cpp:66
pressureObserver::totalLoading_right
double totalLoading_right
Definition: pressure_observer.h:71
pressureObserver::cellLoading_left
double cellLoading_left
Definition: pressure_observer.h:73
pressureObserver::updateContactState
void updateContactState()
Definition: pressure_observer.cpp:147
pressureObserver::padForce_left_prev
double padForce_left_prev
Definition: pressure_observer.h:67
pressureObserver
Definition: pressure_observer.h:50
pressureObserver::pressure_thresh_prev
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_prev
Definition: pressure_observer.h:84
pressureObserver::updateTotalLoading
void updateTotalLoading()
Definition: pressure_observer.cpp:164
pressureObserver::subSample_steps
int subSample_steps
Definition: pressure_observer.h:108
pressureObserver::lfForce_left
double lfForce_left
Definition: pressure_observer.h:76
pressureObserver::spin
void spin()
Definition: pressure_observer.cpp:44
digitalFilter
Definition: digitalFilter.h:23
pressureObserver::subSample_cnt
int subSample_cnt
Definition: pressure_observer.h:107
pressureObserver::pressure_thresh_now
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_now
Definition: pressure_observer.h:84
hardware_interface.h
pressureObserver::updatePressureState
bool updatePressureState()
Definition: pressure_observer.cpp:235
pressureObserver::updateZeros2
void updateZeros2()
Definition: pressure_observer.cpp:206
pressureObserver::zero_cnt
int zero_cnt
Definition: pressure_observer.h:110
pressureObserver::zero_samples
int zero_samples
Definition: pressure_observer.h:109
pressureObserver::right_finger
pr2_hardware_interface::PressureSensor * right_finger
Definition: pressure_observer.h:105
pressureObserver::graspContact
bool graspContact(int contactsDesired)
Definition: pressure_observer.cpp:129
pressureObserver::pressureLFFilt_right
digitalFilter * pressureLFFilt_right[22]
Definition: pressure_observer.h:90
pressureObserver::~pressureObserver
~pressureObserver()
Definition: pressure_observer.cpp:383
pressureObserver::lfForce_right
double lfForce_right
Definition: pressure_observer.h:76
pressureObserver::padForce_right_prev
double padForce_right_prev
Definition: pressure_observer.h:69
pressureObserver::pressure_cur_bias
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_cur_bias
Definition: pressure_observer.h:86
pressureObserver::padForce_left_cur_nonbiased
double padForce_left_cur_nonbiased
Definition: pressure_observer.h:68
pressureObserver::hpForceTrigger
double hpForceTrigger
Definition: pressure_observer.h:75
pressureObserver::pressure_prev
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev
Definition: pressure_observer.h:83
pressureObserver::totalLoading_prev
double totalLoading_prev
Definition: pressure_observer.h:72
pressureObserver::left_contact
bool left_contact
Definition: pressure_observer.h:78
pressureObserver::padForce_right_cur
double padForce_right_cur
Definition: pressure_observer.h:69
pressureObserver::padForce_left_cur
double padForce_left_cur
Definition: pressure_observer.h:67
pressureObserver::pressureLFFilt_left
digitalFilter * pressureLFFilt_left[22]
Definition: pressure_observer.h:89
pressureObserver::pressure_current
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_current
Definition: pressure_observer.h:83
pressureObserver::right_contact
bool right_contact
Definition: pressure_observer.h:78
pressureObserver::broken_sensor
bool broken_sensor
Definition: pressure_observer.h:77
pr2_hardware_interface::PressureSensor
pressureObserver::bias_estimator
void bias_estimator()
Definition: pressure_observer.cpp:78
pressureObserver::totalLoading_left
double totalLoading_left
Definition: pressure_observer.h:71
pressureObserver::forceLightest
double forceLightest
Definition: pressure_observer.h:74
pressureObserver::zero
void zero()
Definition: pressure_observer.cpp:219
pressureObserver::placeContact
bool placeContact
Definition: pressure_observer.h:79
pressureObserver::left_finger
pr2_hardware_interface::PressureSensor * left_finger
Definition: pressure_observer.h:104
pressureObserver::updateXYCentroids
void updateXYCentroids()
Definition: pressure_observer.cpp:305
pressureObserver::time_prev
double time_prev
Definition: pressure_observer.h:113
pressureObserver::checkSlip
bool checkSlip(double slip_motion_limit=0.007, double slip_force_limit=0.18)
Definition: pressure_observer.cpp:314
pressureObserver::pressure_prev_bias
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_bias
Definition: pressure_observer.h:86
digitalFilter.h
pressureObserver::checkPlaceContact
bool checkPlaceContact(double dF)
Definition: pressure_observer.cpp:103
pressureObserver::totalLoading
double totalLoading
Definition: pressure_observer.h:72
pressureObserver::pressure_bp
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_bp
Definition: pressure_observer.h:87


pr2_gripper_sensor_controller
Author(s): Joe Romano
autogenerated on Thu Aug 8 2024 02:38:34