gazebo_ros_grasp_hack.h
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003  
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /*
00022  * Desc: 3D position interface.
00023  * Author: Sachin Chitta and John Hsu
00024  * Date: 10 June 2008
00025  * SVN: $Id$
00026  */
00027 #ifndef GAZEBO_ROS_GRASP_HACK_HH
00028 #define GAZEBO_ROS_GRASP_HACK_HH
00029 
00030 #include <ros/callback_queue.h>
00031 #include <ros/advertise_options.h>
00032 
00033 #include <gazebo/Controller.hh>
00034 #include <gazebo/Entity.hh>
00035 #include <gazebo/Model.hh>
00036 #include <gazebo/Body.hh>
00037 #include <gazebo/Joint.hh>
00038 #include <gazebo/Param.hh>
00039 #include <gazebo/Time.hh>
00040 #include <gazebo/Pose3d.hh>
00041 
00042 #include <ros/ros.h>
00043 #include "boost/thread/mutex.hpp"
00044 #include <std_msgs/String.h>
00045 
00046 namespace gazebo
00047 {
00050 
00098    class GazeboRosGraspHack : public Controller
00099    {
00101       public: GazeboRosGraspHack(Entity *parent );
00102 
00104       public: virtual ~GazeboRosGraspHack();
00105 
00108       protected: virtual void LoadChild(XMLConfigNode *node);
00109 
00111       protected: virtual void InitChild();
00112 
00114       protected: virtual void UpdateChild();
00115 
00117       protected: virtual void FiniChild();
00118 
00120       private: Body *myParentBody;
00121 
00123       private: Model *myParentModel;
00124 
00126       private: Body* l_gripper_palm_body;
00127       private: Body* r_gripper_palm_body;
00128       private: Body* l_gripper_l_finger_tip_body;
00129       private: Body* l_gripper_r_finger_tip_body;
00130       private: Body* r_gripper_l_finger_tip_body;
00131       private: Body* r_gripper_r_finger_tip_body;
00132 
00133       private: Joint* l_gripper_l_finger_joint;
00134       private: Joint* l_gripper_r_finger_joint;
00135       private: Joint* l_gripper_l_finger_tip_joint;
00136       private: Joint* l_gripper_r_finger_tip_joint;
00137 
00138       private: Joint* r_gripper_l_finger_joint;
00139       private: Joint* r_gripper_r_finger_joint;
00140       private: Joint* r_gripper_l_finger_tip_joint;
00141       private: Joint* r_gripper_r_finger_tip_joint;
00142 
00143       private: bool l_grasp;
00144       private: bool r_grasp;
00145 
00146       private: Pose3d l_grasp_relative_pose;
00147       private: double l_gripper_r_finger_joint_position;
00148       private: double l_gripper_l_finger_joint_position;
00149       private: double l_gripper_r_finger_tip_joint_position;
00150       private: double l_gripper_l_finger_tip_joint_position;
00151 
00152       private: Pose3d r_grasp_relative_pose;
00153       private: double r_gripper_r_finger_joint_position;
00154       private: double r_gripper_l_finger_joint_position;
00155       private: double r_gripper_r_finger_tip_joint_position;
00156       private: double r_gripper_l_finger_tip_joint_position;
00157 
00159       private: ros::NodeHandle* rosnode_;
00160       private: ros::Publisher pub_;
00161 
00163       private: ParamT<std::string> *topicNameP;
00164       private: std::string topicName;
00165 
00167       private: ParamT<Vector3> *xyzOffsetsP;
00168       private: Vector3 xyzOffsets;
00169       private: ParamT<Vector3> *rpyOffsetsP;
00170       private: Vector3 rpyOffsets;
00171 
00173       private: boost::mutex lock;
00174 
00176       private: Time last_time;
00177 
00179       private: ParamT<std::string> *robotNamespaceP;
00180       private: std::string robotNamespace;
00181 
00183       private: int graspHackConnectCount;
00184       private: void GraspHackConnect();
00185       private: void GraspHackDisconnect();
00186 
00187       private: ros::CallbackQueue grasp_hack_queue_;
00188       private: void GraspHackQueueThread();
00189       private: boost::thread callback_queue_thread_;
00190 
00191    };
00192 
00194 
00195 
00196 
00197 }
00198 
00199 #endif
00200 


pr2_arm_gazebo
Author(s): John Hsu
autogenerated on Mon Jan 6 2014 12:02:20