Public Member Functions | Private Attributes
GraspChair Class Reference

This class describe the grasping and correction of the grasp position. More...

#include <grasp_chair.h>

List of all members.

Public Member Functions

void correction (simple_robot_control::Arm &arm, char lr, tf::StampedTransform corrGrasp, tf::StampedTransform preGrasp, tf::StampedTransform goalGrasp)
 Correction of the grasp position if necessary.
bool grasp (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 Service call for grasping the chair.
 GraspChair (simple_robot_control::Robot *robot, Gripper *gripper)
bool release (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 Service call for releasing the grasp and returning to start position.
void setGraspPositions_cb (const PointCloud::ConstPtr &msg)
 Set the current grasp position.

Private Attributes

Grippergripper
geometry_msgs::PointStamped left_Gripper
bool position_set
geometry_msgs::PointStamped right_Gripper
simple_robot_control::Robot * robot

Detailed Description

This class describe the grasping and correction of the grasp position.

The grasp positions will be set with the setGraspPosition_cb. The idea for grasping the object is that the robot first move his arms into a preGrasp_position. From there it is possible to grasp the chair safely. If we can't grasp the chair successfully we must manipulate the chair. For a 100% correction of the orientation of the chair we need some knowledge about the pivot of the chair. Because we haven't this knowledge, we could only use a simple try for correction. We have to realize in which direction the chair is rotated (clockwise, or against clockwise) so we can decide which arm should be used for the correction. At this point we affect a hard assumption, because we presuppose that we can grasp the gripper_point which is closer to the robot. So, we grasp the closer gripper_point and move him to another new position. With the service_call the program will start again...

Definition at line 29 of file grasp_chair.h.


Constructor & Destructor Documentation

GraspChair::GraspChair ( simple_robot_control::Robot *  robot,
Gripper gripper 
)

Definition at line 13 of file grasp_chair.cpp.


Member Function Documentation

void GraspChair::correction ( simple_robot_control::Arm &  arm,
char  lr,
tf::StampedTransform  corrGrasp,
tf::StampedTransform  preGrasp,
tf::StampedTransform  goalGrasp 
)

Correction of the grasp position if necessary.

Definition at line 151 of file grasp_chair.cpp.

bool GraspChair::grasp ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Service call for grasping the chair.

Definition at line 19 of file grasp_chair.cpp.

bool GraspChair::release ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Service call for releasing the grasp and returning to start position.

Definition at line 127 of file grasp_chair.cpp.

void GraspChair::setGraspPositions_cb ( const PointCloud::ConstPtr &  msg)

Set the current grasp position.

Definition at line 161 of file grasp_chair.cpp.


Member Data Documentation

Definition at line 46 of file grasp_chair.h.

geometry_msgs::PointStamped GraspChair::left_Gripper [private]

Definition at line 49 of file grasp_chair.h.

Definition at line 50 of file grasp_chair.h.

geometry_msgs::PointStamped GraspChair::right_Gripper [private]

Definition at line 48 of file grasp_chair.h.

simple_robot_control::Robot* GraspChair::robot [private]

Definition at line 47 of file grasp_chair.h.


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


grasp_motion
Author(s): Jan Metzger
autogenerated on Wed Dec 26 2012 16:32:25