$search

gazebo::GazeboRosGraspHack Class Reference

#include <gazebo_ros_grasp_hack.h>

List of all members.

Classes

class  GripperPose

Public Member Functions

 GazeboRosGraspHack (Entity *parent)
 Constructor.
virtual ~GazeboRosGraspHack ()
 Destructor.

Protected Member Functions

virtual void FiniChild ()
 Finalize the controller.
virtual void InitChild ()
 Init the controller.
virtual void LoadChild (XMLConfigNode *node)
 Load the controller.
virtual void UpdateChild ()
 Update the controller.

Private Member Functions

void CheckForGrasps ()
void GetGripperLinks ()
void GraspHackConnect ()
void GraspHackDisconnect ()
void GraspHackQueueThread ()

Private Attributes

boost::thread callback_queue_thread_
bool found_gripper_links
boost::thread get_gripper_links_thread_
ros::CallbackQueue grasp_hack_queue_
double graspCheckRate
ParamT< double > * graspCheckRateP
int graspHackConnectCount
 Keep track of number of connctions.
std::map< std::string,
GripperPose
gripper_bodies
 gripper links and store relative poses for contact correction during grasp
std::vector< Pose3d > gripper_relative_poses
bool l_grasp
Pose3d l_grasp_relative_pose
 object pose relative to wrist_roll_body during grasp
Body * l_wrist_roll_body
 The gripper links.
Time last_grasp_check_time
Time last_time
 save last_time
boost::mutex lock
 A mutex to lock access to fields that are used in message callbacks.
Body * myParentBody
 The parent Body.
Model * myParentModel
 The parent Model.
ros::Publisher pub_
bool r_grasp
Pose3d r_grasp_relative_pose
Body * r_wrist_roll_body
std::string robotNamespace
ParamT< std::string > * robotNamespaceP
 for setting ROS name space
ros::NodeHandlerosnode_
 pointer to ros node
std::string topicName
ParamT< std::string > * topicNameP
 topic name

Detailed Description

Definition at line 50 of file gazebo_ros_grasp_hack.h.


Constructor & Destructor Documentation

GazeboRosGraspHack::GazeboRosGraspHack ( Entity *  parent  ) 

Constructor.

Definition at line 46 of file gazebo_ros_grasp_hack.cpp.

GazeboRosGraspHack::~GazeboRosGraspHack (  )  [virtual]

Destructor.

Definition at line 98 of file gazebo_ros_grasp_hack.cpp.


Member Function Documentation

void GazeboRosGraspHack::CheckForGrasps (  )  [private]

Definition at line 202 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::FiniChild (  )  [protected, virtual]

Finalize the controller.

Definition at line 399 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::GetGripperLinks (  )  [private]

Definition at line 162 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::GraspHackConnect (  )  [private]

Definition at line 140 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::GraspHackDisconnect (  )  [private]

Definition at line 146 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::GraspHackQueueThread (  )  [private]

Definition at line 410 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::InitChild (  )  [protected, virtual]

Init the controller.

Definition at line 153 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::LoadChild ( XMLConfigNode *  node  )  [protected, virtual]

Load the controller.

Parameters:
node XML config node

Definition at line 108 of file gazebo_ros_grasp_hack.cpp.

void GazeboRosGraspHack::UpdateChild (  )  [protected, virtual]

Update the controller.

Definition at line 289 of file gazebo_ros_grasp_hack.cpp.


Member Data Documentation

Definition at line 133 of file gazebo_ros_grasp_hack.h.

Definition at line 115 of file gazebo_ros_grasp_hack.h.

Definition at line 134 of file gazebo_ros_grasp_hack.h.

Definition at line 131 of file gazebo_ros_grasp_hack.h.

Definition at line 110 of file gazebo_ros_grasp_hack.h.

Definition at line 109 of file gazebo_ros_grasp_hack.h.

Keep track of number of connctions.

Definition at line 127 of file gazebo_ros_grasp_hack.h.

std::map<std::string, GripperPose > gazebo::GazeboRosGraspHack::gripper_bodies [private]

gripper links and store relative poses for contact correction during grasp

Definition at line 91 of file gazebo_ros_grasp_hack.h.

Definition at line 92 of file gazebo_ros_grasp_hack.h.

Definition at line 94 of file gazebo_ros_grasp_hack.h.

object pose relative to wrist_roll_body during grasp

Definition at line 98 of file gazebo_ros_grasp_hack.h.

The gripper links.

Definition at line 87 of file gazebo_ros_grasp_hack.h.

Definition at line 111 of file gazebo_ros_grasp_hack.h.

save last_time

Definition at line 120 of file gazebo_ros_grasp_hack.h.

boost::mutex gazebo::GazeboRosGraspHack::lock [private]

A mutex to lock access to fields that are used in message callbacks.

Definition at line 114 of file gazebo_ros_grasp_hack.h.

The parent Body.

Definition at line 81 of file gazebo_ros_grasp_hack.h.

The parent Model.

Definition at line 84 of file gazebo_ros_grasp_hack.h.

Definition at line 103 of file gazebo_ros_grasp_hack.h.

Definition at line 95 of file gazebo_ros_grasp_hack.h.

Definition at line 99 of file gazebo_ros_grasp_hack.h.

Definition at line 88 of file gazebo_ros_grasp_hack.h.

Definition at line 124 of file gazebo_ros_grasp_hack.h.

ParamT<std::string>* gazebo::GazeboRosGraspHack::robotNamespaceP [private]

for setting ROS name space

Definition at line 123 of file gazebo_ros_grasp_hack.h.

pointer to ros node

Definition at line 102 of file gazebo_ros_grasp_hack.h.

Definition at line 107 of file gazebo_ros_grasp_hack.h.

ParamT<std::string>* gazebo::GazeboRosGraspHack::topicNameP [private]

topic name

Definition at line 106 of file gazebo_ros_grasp_hack.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Sat Mar 2 13:40:08 2013