Public Member Functions | Public Attributes | Private Attributes
PenGripper Class Reference

#include <pen_gripper.h>

List of all members.

Public Member Functions

void close_gripper (const string gripper)
void grip_pen ()
bool handle_req (portrait_robot_msgs::alubsc_node_instr::Request &req, portrait_robot_msgs::alubsc_node_instr::Response &res)
void narrow_stereo_cb (const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
void open_gripper (const string gripper)
 PenGripper (ros::NodeHandle &nh)
 constructor
void reset ()
void take_start_position ()
 ~PenGripper ()
 destructor

Public Attributes

bool abort
 if false the pen gripper is active
portrait_robot_msgs::alubsc_status_msg status
 status msg to the gui
ros::ServiceClient status_clt
 status client for the status communication
bool success
 action success

Private Attributes

EECartImpedArm * arm_l
EECartImpedArm * arm_r
actionlib::SimpleActionClient
< pr2_controllers_msgs::Pr2GripperCommandAction > * 
GripperLeft
actionlib::SimpleActionClient
< pr2_controllers_msgs::Pr2GripperCommandAction > * 
GripperRight
actionlib::SimpleActionClient
< pr2_controllers_msgs::PointHeadAction > * 
head
pcl::PointXYZ l_start_pos
ros::Publisher marker_middle_pub
ros::NodeHandlen
ros::Publisher pcl_pub
ros::Subscriber pcl_sub
pcl::PointCloud< pcl::PointXYZ > pen_cloud
pcl::PointXYZ r_start_pos
pen red_pen
tf::TransformListener tflistener

Detailed Description

Definition at line 68 of file pen_gripper.h.


Constructor & Destructor Documentation

constructor

Definition at line 33 of file pen_gripper.cpp.

destructor

Definition at line 23 of file pen_gripper.cpp.


Member Function Documentation

void PenGripper::close_gripper ( const string  gripper)

close the gripper

Parameters:
grippercan be left or right

Definition at line 154 of file pen_gripper.cpp.

try to grip the pen when its ready and take it into an end position

Definition at line 528 of file pen_gripper.cpp.

handles the client requests

Definition at line 600 of file pen_gripper.cpp.

void PenGripper::narrow_stereo_cb ( const sensor_msgs::PointCloud2ConstPtr &  cloud_msg)

locate the pen head head position over the table from a narrow_stereo_textured point cloud only when a request is send. if the table is found, the mid point of the pen will be the pen position and the pen status is set to ready. assumptions: 1. The pen stands in the gripping range/narrow stereo range 2. The pen is longer than 0.10 m. 3. The pen head is the highest point over the table surface 4. The table surface is at least 0.60 m high

Definition at line 297 of file pen_gripper.cpp.

void PenGripper::open_gripper ( const string  gripper)

open the gripper

Parameters:
grippercan be left or right

Definition at line 100 of file pen_gripper.cpp.

reset the pen gripper variables to the start values

Definition at line 589 of file pen_gripper.cpp.

start the projector, move the head to a fixed position to look at the table surface, move the gripper in a start position at the right/left side of the pr2

Definition at line 210 of file pen_gripper.cpp.


Member Data Documentation

if false the pen gripper is active

Definition at line 111 of file pen_gripper.h.

EECartImpedArm * PenGripper::arm_l [private]

Definition at line 76 of file pen_gripper.h.

EECartImpedArm* PenGripper::arm_r [private]

Definition at line 76 of file pen_gripper.h.

Definition at line 87 of file pen_gripper.h.

Definition at line 86 of file pen_gripper.h.

Definition at line 83 of file pen_gripper.h.

pcl::PointXYZ PenGripper::l_start_pos [private]

Definition at line 80 of file pen_gripper.h.

Definition at line 100 of file pen_gripper.h.

Definition at line 73 of file pen_gripper.h.

Definition at line 97 of file pen_gripper.h.

Definition at line 96 of file pen_gripper.h.

pcl::PointCloud<pcl::PointXYZ> PenGripper::pen_cloud [private]

Definition at line 90 of file pen_gripper.h.

pcl::PointXYZ PenGripper::r_start_pos [private]

Definition at line 79 of file pen_gripper.h.

Definition at line 93 of file pen_gripper.h.

status msg to the gui

Definition at line 114 of file pen_gripper.h.

status client for the status communication

Definition at line 117 of file pen_gripper.h.

action success

Definition at line 108 of file pen_gripper.h.

Definition at line 103 of file pen_gripper.h.


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


pen_gripper
Author(s): Richard Schneider
autogenerated on Wed Dec 26 2012 16:16:39