pr2_gripper_sensor_controller.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 pr2_gripper_sensor_controller.cpp - controller to read data from
40 // the sensors on the pr2 gripper (accelerometer in palm,
41 // pressure arrays on the fingers, and encoder in the hand)
42 // and publish higher-level useful processed information about
43 // them, as well as perform low-level control tasks to control
44 // the gripper based on these signals in real-time.
45 //
46 // This controller is inteded to be interacted with through its
47 // action interface, pr2_gripper_sensor_action.
48 
54 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactData.h>
55 #include <pr2_gripper_sensor_msgs/PR2GripperFindContactCommand.h>
56 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoData.h>
57 #include <pr2_gripper_sensor_msgs/PR2GripperForceServoCommand.h>
58 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoData.h>
59 #include <pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand.h>
60 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorData.h>
61 #include <pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand.h>
62 #include <pr2_gripper_sensor_msgs/PR2GripperSensorRTState.h>
63 #include <pr2_gripper_sensor_msgs/PR2GripperSensorRawData.h>
64 #include <std_srvs/Empty.h>
65 #include <std_msgs/Empty.h>
66 
67 #include <ros/ros.h>
68 
69 #include <pr2_controllers_msgs/JointControllerState.h>
70 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
71 #include <boost/scoped_ptr.hpp>
72 #include <boost/thread/condition.hpp>
75 #include <std_msgs/Float64.h>
76 
77 
79 
81 {
82 private:
85 
86 
87  // functions ---------------
89  bool forceServo();
90  bool updateZeros(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
91  bool stopMotorOutput(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
92  void reinitializeValues();
93  bool reloadParams(std_srvs::Empty::Request& req,std_srvs::Empty::Response& resp);
94 
95  // variables ---------------
99  bool placedState;
102  double acc_trigger;
103  double slip_trigger;
107 
108  // state variables about our controller
111  double servo_force;
112  double servo_position;
113  double max_effort;
114  double servo_velocity;
120  const pr2_gripper_sensor_msgs::PR2GripperSensorRTState rt_state_def;
121  pr2_gripper_sensor_msgs::PR2GripperSensorRawData raw_data;
123 
125 
129 
130 
135 
137  std_srvs::Empty::Request empty_req;
138  std_srvs::Empty::Response empty_resp;
139 
140 
142  boost::scoped_ptr<
144  pr2_gripper_sensor_msgs::PR2GripperSensorRawData> > raw_data_publisher_ ;
145 
147  boost::scoped_ptr<
149  pr2_controllers_msgs::JointControllerState> > controller_state_publisher_ ;
151  void positionCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr& msg);
152 
154  boost::scoped_ptr<
156  pr2_gripper_sensor_msgs::PR2GripperFindContactData> > contact_state_publisher_ ;
158  void findContactCB(const pr2_gripper_sensor_msgs::PR2GripperFindContactCommandConstPtr& msg);
159 
161  boost::scoped_ptr<
163  pr2_gripper_sensor_msgs::PR2GripperSlipServoData> > slip_state_publisher_ ;
165  void slipServoCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoCommandConstPtr& msg);
166 
168  boost::scoped_ptr<
170  pr2_gripper_sensor_msgs::PR2GripperForceServoData> > force_state_publisher_ ;
172  void forceServoCB(const pr2_gripper_sensor_msgs::PR2GripperForceServoCommandConstPtr& msg);
173 
175  boost::scoped_ptr<
177  pr2_gripper_sensor_msgs::PR2GripperEventDetectorData> > event_detector_state_publisher_ ;
179  void eventDetectorCB(const pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommandConstPtr& msg);
180 
181 public:
182  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
183  virtual void update();
184  virtual void stopping();
185  virtual void starting() {}
186 
187 };
188 }
double servo_force
the force we want to servo our controller to
int control_mode
the current/desired control mode we want the controller state machine to be in
std_srvs::Empty::Request empty_req
blank request/responses
bool publish_raw_data
flag to indicate whether we want to publish raw data or not
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_gripper_sensor_msgs::PR2GripperFindContactData > > contact_state_publisher_
find_contact real-time publisher
int placeConditions
storage container for the conditions we want to use in event_detector
bool reloadParams(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
double fingertip_start_force
the force we want to start seroing to on the fingertips
double servo_position
the position we want to servo our controller to
int contacts_desired
the contact state we want when we search for contact on the fingers
void positionCB(const pr2_controllers_msgs::Pr2GripperCommandConstPtr &msg)
bool stopMotorOutput(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_gripper_sensor_msgs::PR2GripperSensorRawData > > raw_data_publisher_
raw data real-time publisher
int contactCounter
counter to delay a certain amount of tmie after contact
double slip_trigger
value to use as trigger for slip detection (event_detector)
int findContact_delay
counter to track how long a force is stable for
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_gripper_sensor_msgs::PR2GripperSlipServoData > > slip_state_publisher_
slip_servo real-time publisher
double max_effort
the max effort to allow our controller to use
accelerationObserver * myAccelerationObserver
accelerometer observer object
double fingertip_force_limit
the limit we do not want to exceed when force servoing
void slipServoCB(const pr2_gripper_sensor_msgs::PR2GripperSlipServoCommandConstPtr &msg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_gripper_sensor_msgs::PR2GripperEventDetectorData > > event_detector_state_publisher_
place publisher and listener
bool update_zeros
bool to signal whether we are currently updating our zeros or not
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
double acc_trigger
value to use as trigger for acceleration detection (event_detector)
bool updateZeros(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_gripper_sensor_msgs::PR2GripperForceServoData > > force_state_publisher_
force_servo real-time publisher
void forceServoCB(const pr2_gripper_sensor_msgs::PR2GripperForceServoCommandConstPtr &msg)
bool stable_contact
state variable to indicate whether our contact has been held enough
gripperController * myGripperController
gripper action object to control our gripper
pressureObserver * myPressureObserver
pressure observer object to do analysis on the incoming pressure sensor data
int publish_skip
skip count when publishing controller information
void findContactCB(const pr2_gripper_sensor_msgs::PR2GripperFindContactCommandConstPtr &msg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
position data real-time publisher
pr2_gripper_sensor_msgs::PR2GripperSensorRawData raw_data
an object for raw data publication for debugging
double force_servo_velocity_tolerance
the tolerance on velocity to consider a force stable
bool stable_force
flag to indicate a stable force is achieved
pr2_mechanism_model::RobotState * robotHandle
our robot state handle
bool initializeHandles(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
const pr2_gripper_sensor_msgs::PR2GripperSensorRTState rt_state_def
object that defines states of our controller
double servo_velocity
the velocity we would like our controller to servo to
void eventDetectorCB(const pr2_gripper_sensor_msgs::PR2GripperEventDetectorCommandConstPtr &msg)
double deformation_limit
the max allowable deformation for our controller
bool placedState
state flag to indicate when event_detector succceded
bool contact_success
flag to indicate whether the fingers found contact or not


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