Public Member Functions | Protected Attributes
VisualServoNode Class Reference

List of all members.

Public Member Functions

void close ()
cv::Mat colorSegment (cv::Mat color_frame, int hue, int threshold)
cv::Mat colorSegment (cv::Mat color_frame, int _hue_n, int _hue_p, int _sat_n, int _sat_p, int _value_n, int _value_p)
void executeStatemachine ()
void executeStatemachine ()
std::vector< cv::Moments > findMoments (cv::Mat in, cv::Mat &color_frame, unsigned int max_num=3)
visual_servo::VisualServoPose formPoseService (float px, float py, float pz)
visual_servo::VisualServoPose formPoseService (float px, float py, float pz)
float getError (std::vector< VSXYZ > a, std::vector< VSXYZ > b)
std::vector< cv::PointgetMomentCoordinates (std::vector< cv::Moments > ms)
float getTipDistance ()
visual_servo::VisualServoTwist getTwist (std::vector< VSXYZ > desire)
bool grab ()
bool initializeDesired (VSXYZ &vDesire)
bool initializeDesired (tabletop_pushing::ProtoObjects &pos)
void initializeService ()
void initializeService ()
void open ()
void place ()
void placeDoneCB (const actionlib::SimpleClientGoalState &state, const pr2_gripper_sensor_msgs::PR2GripperEventDetectorResultConstPtr &result)
void printMatrix (cv::Mat_< double > in)
void printMatrix (cv::Mat_< double > in)
void release ()
void releaseDoneCB (const actionlib::SimpleClientGoalState &state, const pr2_gripper_sensor_msgs::PR2GripperReleaseResultConstPtr &result)
void reset ()
bool sendZeroVelocity ()
bool sendZeroVelocity ()
void sensorCallback (const sensor_msgs::ImageConstPtr &img_msg, const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
void sensorCallback (const sensor_msgs::ImageConstPtr &img_msg, const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
void setDisplay ()
void setDisplay ()
bool setGoalForAnObject (std::vector< VSXYZ > &goal, PoseStamped &goal_p, tabletop_pushing::ProtoObject po)
bool setGoalForAnObject (std::vector< VSXYZ > &goal, PoseStamped &goal_p, VSXYZ desire)
void setSleepNonblock (float time)
bool sleepNonblock ()
void spin ()
void spin ()
bool updateGripperFeatures ()
 VisualServoNode (ros::NodeHandle &n)
 VisualServoNode (ros::NodeHandle &n)
 ~VisualServoNode ()
 ~VisualServoNode ()

Protected Attributes

ros::Time alarm_
sensor_msgs::CameraInfo cam_info_
std::string cam_info_topic_
bool camera_initialized_
ros::Publisher chatter_pub_
float close_gripper_dist_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
cloud_sub_
std_msgs::Header cur_camera_header_
cv::Mat cur_color_frame_
cv::Mat cur_depth_frame_
std::vector< VSXYZcur_goal_
cv::Mat cur_orig_color_frame_
XYZPointCloud cur_point_cloud_
cv::Mat cur_workspace_mask_
int default_sat_bot_value_
int default_sat_top_value_
int default_val_value_
message_filters::Subscriber
< sensor_msgs::Image > 
depth_sub_
bool desire_points_initialized_
VSXYZ desired_
cv::Mat desired_jacobian_
EventDetectorClientdetector_client_
int display_wait_ms_
std::vector< VSXYZgoal_
PoseStamped goal_p_
GrabClientgrab_client_
GripperClientgripper_client_
bool gripper_pose_estimated_
GripperTape gripper_tape_
int gripper_tape_hue_threshold_
int gripper_tape_hue_value_
bool have_depth_data_
ros::ServiceClient i_client_
message_filters::Subscriber
< sensor_msgs::Image > 
image_sub_
bool is_detected_
bool is_gripper_initialized_
image_transport::ImageTransport it_
int jacobian_type_
cv::Mat K
VisualServoClientl_vs_client_
double min_contour_size_
ros::NodeHandle n_
ros::NodeHandle n_private_
int num_downsamples_
float object_z_
std::string optical_frame_
cv::Rect original_box_
ros::ServiceClient p_client_
unsigned int PHASE
bool place_detection_
double place_z_velocity_
tabletop_pushing::ProtoObjects po_
double pose_servo_z_offset_
VisualServoClientr_vs_client_
ReleaseClientrelease_client_
message_filters::Synchronizer
< MySyncPolicy
sync_
double tape1_offset_x_
double tape1_offset_y_
double tape1_offset_z_
std::vector< VSXYZtape_features_
PoseStamped tape_features_p_
int target_hue_threshold_
int target_hue_value_
std::vector< cv::Pointtemp_draw_
shared_ptr< tf::TransformListenertf_
int tracker_count_
ros::ServiceClient v_client_
std::vector< pcl::PointXYZ > v_fk_diff_
shared_ptr< VisualServovs_
double vs_err_term_threshold_
std::string workspace_frame_

Detailed Description

Definition at line 208 of file vs_grasp.cpp.


Constructor & Destructor Documentation

Definition at line 211 of file vs_grasp.cpp.

Definition at line 267 of file vs_grasp.cpp.

Definition at line 137 of file vs_pose.cpp.

Definition at line 184 of file vs_pose.cpp.


Member Function Documentation

void VisualServoNode::close ( ) [inline]

Definition at line 831 of file vs_grasp.cpp.

cv::Mat VisualServoNode::colorSegment ( cv::Mat  color_frame,
int  hue,
int  threshold 
) [inline]

Definition at line 1388 of file vs_grasp.cpp.

cv::Mat VisualServoNode::colorSegment ( cv::Mat  color_frame,
int  _hue_n,
int  _hue_p,
int  _sat_n,
int  _sat_p,
int  _value_n,
int  _value_p 
) [inline]

Very Basic Color Segmentation done in HSV space Takes in Hue value and threshold as input to compute the distance in color space

Parameters:
color_framecolor input from image
Returns:
mask from the color segmentation

Definition at line 1408 of file vs_grasp.cpp.

Definition at line 234 of file vs_pose.cpp.

Definition at line 331 of file vs_grasp.cpp.

std::vector<cv::Moments> VisualServoNode::findMoments ( cv::Mat  in,
cv::Mat &  color_frame,
unsigned int  max_num = 3 
) [inline]
Parameters:
insingle channel image input
color_frameneed the original image for debugging and imshow
Returns:
returns ALL moment of specific color in the image

Definition at line 1359 of file vs_grasp.cpp.

visual_servo::VisualServoPose VisualServoNode::formPoseService ( float  px,
float  py,
float  pz 
) [inline]

Definition at line 351 of file vs_pose.cpp.

visual_servo::VisualServoPose VisualServoNode::formPoseService ( float  px,
float  py,
float  pz 
) [inline]

Definition at line 1465 of file vs_grasp.cpp.

float VisualServoNode::getError ( std::vector< VSXYZ a,
std::vector< VSXYZ b 
) [inline]

Definition at line 1253 of file vs_grasp.cpp.

Take three biggest moments of specific color and returns the three biggest blobs or moments. This method assumes that the features are in QR code like configuration

Parameters:
msAll moments of color segmented
Returns:
returns vectors of cv::Point. Ordered in specific way (1. top left, 2. top right, and 3. bottom left)

Definition at line 1282 of file vs_grasp.cpp.

float VisualServoNode::getTipDistance ( ) [inline]

Definition at line 678 of file vs_grasp.cpp.

visual_servo::VisualServoTwist VisualServoNode::getTwist ( std::vector< VSXYZ desire) [inline]

Definition at line 1158 of file vs_grasp.cpp.

Definition at line 858 of file vs_grasp.cpp.

Definition at line 929 of file vs_grasp.cpp.

bool VisualServoNode::initializeDesired ( tabletop_pushing::ProtoObjects &  pos) [inline]

Definition at line 1017 of file vs_grasp.cpp.

Definition at line 320 of file vs_pose.cpp.

Definition at line 1131 of file vs_grasp.cpp.

void VisualServoNode::open ( ) [inline]

Definition at line 844 of file vs_grasp.cpp.

void VisualServoNode::place ( ) [inline]

Gripper Actions: These are all blocking

Definition at line 807 of file vs_grasp.cpp.

void VisualServoNode::placeDoneCB ( const actionlib::SimpleClientGoalState state,
const pr2_gripper_sensor_msgs::PR2GripperEventDetectorResultConstPtr &  result 
) [inline]

Definition at line 821 of file vs_grasp.cpp.

void VisualServoNode::printMatrix ( cv::Mat_< double >  in) [inline]

Definition at line 356 of file vs_pose.cpp.

void VisualServoNode::printMatrix ( cv::Mat_< double >  in) [inline]

Definition at line 1470 of file vs_grasp.cpp.

void VisualServoNode::release ( ) [inline]

Definition at line 876 of file vs_grasp.cpp.

void VisualServoNode::releaseDoneCB ( const actionlib::SimpleClientGoalState state,
const pr2_gripper_sensor_msgs::PR2GripperReleaseResultConstPtr &  result 
) [inline]

Definition at line 891 of file vs_grasp.cpp.

void VisualServoNode::reset ( ) [inline]

Definition at line 705 of file vs_grasp.cpp.

Definition at line 341 of file vs_pose.cpp.

Definition at line 1455 of file vs_grasp.cpp.

void VisualServoNode::sensorCallback ( const sensor_msgs::ImageConstPtr &  img_msg,
const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::PointCloud2ConstPtr &  cloud_msg 
) [inline]

Called when Kinect information is avaiable. Refresh rate of about 30Hz

Definition at line 191 of file vs_pose.cpp.

void VisualServoNode::sensorCallback ( const sensor_msgs::ImageConstPtr &  img_msg,
const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::PointCloud2ConstPtr &  cloud_msg 
) [inline]

Called when Kinect information is avaiable. Refresh rate of about 30Hz

Definition at line 278 of file vs_grasp.cpp.

void VisualServoNode::setDisplay ( ) [inline]

Definition at line 314 of file vs_pose.cpp.

void VisualServoNode::setDisplay ( ) [inline]

Definition at line 714 of file vs_grasp.cpp.

bool VisualServoNode::setGoalForAnObject ( std::vector< VSXYZ > &  goal,
PoseStamped &  goal_p,
tabletop_pushing::ProtoObject  po 
) [inline]

Definition at line 1066 of file vs_grasp.cpp.

bool VisualServoNode::setGoalForAnObject ( std::vector< VSXYZ > &  goal,
PoseStamped &  goal_p,
VSXYZ  desire 
) [inline]

Definition at line 1104 of file vs_grasp.cpp.

void VisualServoNode::setSleepNonblock ( float  time) [inline]

HELPER

Definition at line 907 of file vs_grasp.cpp.

Definition at line 913 of file vs_grasp.cpp.

void VisualServoNode::spin ( ) [inline]

Executive control function for launching the node.

Definition at line 370 of file vs_pose.cpp.

void VisualServoNode::spin ( ) [inline]

Executive control function for launching the node.

Definition at line 1484 of file vs_grasp.cpp.

Definition at line 1179 of file vs_grasp.cpp.


Member Data Documentation

Definition at line 1559 of file vs_grasp.cpp.

sensor_msgs::CameraInfo VisualServoNode::cam_info_ [protected]

Definition at line 1500 of file vs_grasp.cpp.

std::string VisualServoNode::cam_info_topic_ [protected]

Definition at line 1519 of file vs_grasp.cpp.

Definition at line 1517 of file vs_grasp.cpp.

Definition at line 1558 of file vs_grasp.cpp.

Definition at line 1581 of file vs_grasp.cpp.

message_filters::Subscriber< sensor_msgs::PointCloud2 > VisualServoNode::cloud_sub_ [protected]

Definition at line 1497 of file vs_grasp.cpp.

Definition at line 1506 of file vs_grasp.cpp.

cv::Mat VisualServoNode::cur_color_frame_ [protected]

Definition at line 1502 of file vs_grasp.cpp.

cv::Mat VisualServoNode::cur_depth_frame_ [protected]

Definition at line 1504 of file vs_grasp.cpp.

Definition at line 1546 of file vs_grasp.cpp.

Definition at line 1503 of file vs_grasp.cpp.

Definition at line 1507 of file vs_grasp.cpp.

Definition at line 1505 of file vs_grasp.cpp.

Definition at line 1527 of file vs_grasp.cpp.

Definition at line 1528 of file vs_grasp.cpp.

Definition at line 1529 of file vs_grasp.cpp.

message_filters::Subscriber< sensor_msgs::Image > VisualServoNode::depth_sub_ [protected]

Definition at line 1496 of file vs_grasp.cpp.

Definition at line 1518 of file vs_grasp.cpp.

Definition at line 1551 of file vs_grasp.cpp.

Definition at line 1545 of file vs_grasp.cpp.

Definition at line 1570 of file vs_grasp.cpp.

Definition at line 1513 of file vs_grasp.cpp.

Definition at line 1547 of file vs_grasp.cpp.

PoseStamped VisualServoNode::goal_p_ [protected]

Definition at line 1548 of file vs_grasp.cpp.

Definition at line 1568 of file vs_grasp.cpp.

Definition at line 1567 of file vs_grasp.cpp.

Definition at line 1555 of file vs_grasp.cpp.

Definition at line 1582 of file vs_grasp.cpp.

Definition at line 1526 of file vs_grasp.cpp.

Definition at line 1525 of file vs_grasp.cpp.

Definition at line 1512 of file vs_grasp.cpp.

Definition at line 1564 of file vs_grasp.cpp.

message_filters::Subscriber< sensor_msgs::Image > VisualServoNode::image_sub_ [protected]

Definition at line 1495 of file vs_grasp.cpp.

Definition at line 1577 of file vs_grasp.cpp.

Definition at line 1554 of file vs_grasp.cpp.

Definition at line 1499 of file vs_grasp.cpp.

Definition at line 1533 of file vs_grasp.cpp.

cv::Mat VisualServoNode::K [protected]

Definition at line 1552 of file vs_grasp.cpp.

Definition at line 437 of file vs_pose.cpp.

Definition at line 1530 of file vs_grasp.cpp.

Definition at line 1493 of file vs_grasp.cpp.

Definition at line 1494 of file vs_grasp.cpp.

Definition at line 1514 of file vs_grasp.cpp.

float VisualServoNode::object_z_ [protected]

Definition at line 1579 of file vs_grasp.cpp.

std::string VisualServoNode::optical_frame_ [protected]

Definition at line 1516 of file vs_grasp.cpp.

cv::Rect VisualServoNode::original_box_ [protected]

Definition at line 1574 of file vs_grasp.cpp.

Definition at line 1563 of file vs_grasp.cpp.

unsigned int VisualServoNode::PHASE [protected]

Definition at line 1542 of file vs_grasp.cpp.

Definition at line 1578 of file vs_grasp.cpp.

Definition at line 1536 of file vs_grasp.cpp.

tabletop_pushing::ProtoObjects VisualServoNode::po_ [protected]

Definition at line 1585 of file vs_grasp.cpp.

Definition at line 1535 of file vs_grasp.cpp.

Definition at line 438 of file vs_pose.cpp.

Definition at line 1569 of file vs_grasp.cpp.

Definition at line 1498 of file vs_grasp.cpp.

Definition at line 1537 of file vs_grasp.cpp.

Definition at line 1538 of file vs_grasp.cpp.

Definition at line 1539 of file vs_grasp.cpp.

Definition at line 1549 of file vs_grasp.cpp.

PoseStamped VisualServoNode::tape_features_p_ [protected]

Definition at line 1550 of file vs_grasp.cpp.

Definition at line 1524 of file vs_grasp.cpp.

Definition at line 1523 of file vs_grasp.cpp.

Definition at line 1573 of file vs_grasp.cpp.

shared_ptr< tf::TransformListener > VisualServoNode::tf_ [protected]

Definition at line 1501 of file vs_grasp.cpp.

Definition at line 1520 of file vs_grasp.cpp.

Definition at line 1562 of file vs_grasp.cpp.

std::vector<pcl::PointXYZ> VisualServoNode::v_fk_diff_ [protected]

Definition at line 1553 of file vs_grasp.cpp.

shared_ptr< VisualServo > VisualServoNode::vs_ [protected]

Definition at line 1510 of file vs_grasp.cpp.

Definition at line 1534 of file vs_grasp.cpp.

std::string VisualServoNode::workspace_frame_ [protected]

Definition at line 1515 of file vs_grasp.cpp.


The documentation for this class was generated from the following files:


visual_servo
Author(s): Stephan Lee
autogenerated on Wed Nov 27 2013 11:44:03