Go to the documentation of this file.
42 #include <pr2_gripper_sensor_msgs/PR2GripperPressureData.h>
45 #ifndef _PRESSURE_OBSERVER
46 #define _PRESSURE_OBSERVER
48 #define UNITS_PER_N 1600
60 bool checkSlip(
double slip_motion_limit = 0.007,
double slip_force_limit = 0.18);
94 void getPadCentroid(boost::array<double,22> pressureArray,
double *x,
double *y);
100 double getPadForce(boost::array<double,22> pressureArray);
120 #endif // _PRESSURE_OBSERVER
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_zerod
double getPadForce(boost::array< double, 22 > pressureArray)
double padForce_cur_nonbiased
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_current
pressureObserver(pr2_hardware_interface::PressureSensor *left, pr2_hardware_interface::PressureSensor *right)
double padForce_right_cur_nonbiased
int checkSideImpact(double dF)
pr2_gripper_sensor_msgs::PR2GripperPressureData zero_offset
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_now
void getPadCentroid(boost::array< double, 22 > pressureArray, double *x, double *y)
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_current_zerod
void updateBrokenSensorStatus()
double totalLoading_right
void updateContactState()
double padForce_left_prev
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_prev
void updateTotalLoading()
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_thresh_now
bool updatePressureState()
pr2_hardware_interface::PressureSensor * right_finger
bool graspContact(int contactsDesired)
digitalFilter * pressureLFFilt_right[22]
double padForce_right_prev
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_cur_bias
double padForce_left_cur_nonbiased
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev
double padForce_right_cur
digitalFilter * pressureLFFilt_left[22]
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_current
pr2_hardware_interface::PressureSensor * left_finger
bool checkSlip(double slip_motion_limit=0.007, double slip_force_limit=0.18)
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_prev_bias
bool checkPlaceContact(double dF)
pr2_gripper_sensor_msgs::PR2GripperPressureData pressure_bp