acceleration_observer.cpp
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 acceleration_observer.cpp - file to read the hand mounted
40 // accelerometer in the pr2 and do some simple processing to
41 // make the data more accessible to higher-level code
42 
44 
45 // method to be called to check if we saw a contact acceleration
47 {
48  //if(( fabs(aX) > dAcc) || (fabs(aY) > dAcc) || (fabs(aZ) > dAcc)|| placeContact )
49  if( sqrt(aX_bp*aX_bp + aY_bp*aY_bp + aZ_bp*aZ_bp) > dAcc || placeContact)
50  placeContact = true;
51  else
52  placeContact = false;
53  return placeContact;
54 }
55 
56 // method to be called each 1ms timestep in realtime to ensure data collection and manipulation happens properly
58 {
59  // retrieve and filter our acceleration data
60  std::vector<geometry_msgs::Vector3> threeAccs = accHandle->state_.samples_;
61  for( uint i = 0; i < threeAccs.size(); i++ )
62  {
63  aX_bp = accBPFilt[0]->getNextFilteredValue(threeAccs[i].x);
64  aY_bp = accBPFilt[1]->getNextFilteredValue(threeAccs[i].y);
65  aZ_bp = accBPFilt[2]->getNextFilteredValue(threeAccs[i].z);
66 
67  aX_lp = accLPFilt[0]->getNextFilteredValue(threeAccs[i].x);
68  aY_lp = accLPFilt[1]->getNextFilteredValue(threeAccs[i].y);
69  aZ_lp = accLPFilt[2]->getNextFilteredValue(threeAccs[i].z);
71  }
72 
73 }
74 
75 // constructor
77 {
78  accHandle = accelerometerHandle;
79 
80  // place contact flag
81  placeContact = false;
82 
83  // instatiate our acceleration values
84  aX_lp = 0;
85  aY_lp = 0;
86  aZ_lp = 0;
87  aX_bp = 0;
88  aY_bp = 0;
89  aZ_bp = 0;
90 
91  // make sure the accelerometer has a 1.5 khz bandwidth
93 
94  // make sure the accelerometer has a +/- 8g range (0 = 2g, 1 = 4g)
96 
97 
98  // create our filter for band-passed accelerometer data
99  // 1st order chebychev. band-pass 5-1000 hz
100  float b_bpfilt[] = {0.8305, 0, -0.8305};
101  float a_bpfilt[] = {1.0,-0.3329,-0.6610};
102  for(int i=0; i < 3; i++)
103  accBPFilt[i] = new digitalFilter(2, true,b_bpfilt,a_bpfilt);
104 
105  // create our filter for low-passed accelerometer data
106  // 1st order butterworth. low-pass 1000 hz
107  float b_lpfilt[] = {0.634, 0.634};
108  float a_lpfilt[] = {1.0, 0.2679};
109  for(int i=0; i < 3; i++)
110  accLPFilt[i] = new digitalFilter(1, true,b_lpfilt,a_lpfilt);
111 
112 }
113 
114 
115 // destructor
117 {
118  delete[] accBPFilt;
119  delete[] accLPFilt;
120 }
121 
digitalFilter * accLPFilt[3]
bool checkPlaceContact(double dAcc)
float getNextFilteredValue(float u_current)
digitalFilter * accBPFilt[3]
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
pr2_hardware_interface::Accelerometer * accHandle
static Time now()
accelerationObserver(pr2_hardware_interface::Accelerometer *accelerometerHandle)
std::vector< geometry_msgs::Vector3 > samples_


pr2_gripper_sensor_controller
Author(s): Joe Romano
autogenerated on Wed Apr 1 2020 03:58:23