Definition at line 208 of file vs_grasp.cpp.
VisualServoNode::VisualServoNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 211 of file vs_grasp.cpp.
VisualServoNode::~VisualServoNode | ( | ) | [inline] |
Definition at line 267 of file vs_grasp.cpp.
VisualServoNode::VisualServoNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 137 of file vs_pose.cpp.
VisualServoNode::~VisualServoNode | ( | ) | [inline] |
Definition at line 184 of file vs_pose.cpp.
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
color_frame | color input from image |
Definition at line 1408 of file vs_grasp.cpp.
void VisualServoNode::executeStatemachine | ( | ) | [inline] |
Definition at line 234 of file vs_pose.cpp.
void VisualServoNode::executeStatemachine | ( | ) | [inline] |
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] |
in | single channel image input |
color_frame | need the original image for debugging and imshow |
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.
std::vector<cv::Point> VisualServoNode::getMomentCoordinates | ( | std::vector< cv::Moments > | ms | ) | [inline] |
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
ms | All moments of color segmented |
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.
bool VisualServoNode::grab | ( | ) | [inline] |
Definition at line 858 of file vs_grasp.cpp.
bool VisualServoNode::initializeDesired | ( | VSXYZ & | vDesire | ) | [inline] |
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.
void VisualServoNode::initializeService | ( | ) | [inline] |
Definition at line 320 of file vs_pose.cpp.
void VisualServoNode::initializeService | ( | ) | [inline] |
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.
bool VisualServoNode::sendZeroVelocity | ( | ) | [inline] |
Definition at line 341 of file vs_pose.cpp.
bool VisualServoNode::sendZeroVelocity | ( | ) | [inline] |
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.
bool VisualServoNode::sleepNonblock | ( | ) | [inline] |
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.
bool VisualServoNode::updateGripperFeatures | ( | ) | [inline] |
Definition at line 1179 of file vs_grasp.cpp.
ros::Time VisualServoNode::alarm_ [protected] |
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.
bool VisualServoNode::camera_initialized_ [protected] |
Definition at line 1517 of file vs_grasp.cpp.
ros::Publisher VisualServoNode::chatter_pub_ [protected] |
Definition at line 1558 of file vs_grasp.cpp.
float VisualServoNode::close_gripper_dist_ [protected] |
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.
std_msgs::Header VisualServoNode::cur_camera_header_ [protected] |
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.
std::vector<VSXYZ> VisualServoNode::cur_goal_ [protected] |
Definition at line 1546 of file vs_grasp.cpp.
cv::Mat VisualServoNode::cur_orig_color_frame_ [protected] |
Definition at line 1503 of file vs_grasp.cpp.
XYZPointCloud VisualServoNode::cur_point_cloud_ [protected] |
Definition at line 1507 of file vs_grasp.cpp.
cv::Mat VisualServoNode::cur_workspace_mask_ [protected] |
Definition at line 1505 of file vs_grasp.cpp.
int VisualServoNode::default_sat_bot_value_ [protected] |
Definition at line 1527 of file vs_grasp.cpp.
int VisualServoNode::default_sat_top_value_ [protected] |
Definition at line 1528 of file vs_grasp.cpp.
int VisualServoNode::default_val_value_ [protected] |
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.
bool VisualServoNode::desire_points_initialized_ [protected] |
Definition at line 1518 of file vs_grasp.cpp.
VSXYZ VisualServoNode::desired_ [protected] |
Definition at line 1551 of file vs_grasp.cpp.
cv::Mat VisualServoNode::desired_jacobian_ [protected] |
Definition at line 1545 of file vs_grasp.cpp.
EventDetectorClient* VisualServoNode::detector_client_ [protected] |
Definition at line 1570 of file vs_grasp.cpp.
int VisualServoNode::display_wait_ms_ [protected] |
Definition at line 1513 of file vs_grasp.cpp.
std::vector<VSXYZ> VisualServoNode::goal_ [protected] |
Definition at line 1547 of file vs_grasp.cpp.
PoseStamped VisualServoNode::goal_p_ [protected] |
Definition at line 1548 of file vs_grasp.cpp.
GrabClient* VisualServoNode::grab_client_ [protected] |
Definition at line 1568 of file vs_grasp.cpp.
GripperClient* VisualServoNode::gripper_client_ [protected] |
Definition at line 1567 of file vs_grasp.cpp.
bool VisualServoNode::gripper_pose_estimated_ [protected] |
Definition at line 1555 of file vs_grasp.cpp.
GripperTape VisualServoNode::gripper_tape_ [protected] |
Definition at line 1582 of file vs_grasp.cpp.
int VisualServoNode::gripper_tape_hue_threshold_ [protected] |
Definition at line 1526 of file vs_grasp.cpp.
int VisualServoNode::gripper_tape_hue_value_ [protected] |
Definition at line 1525 of file vs_grasp.cpp.
bool VisualServoNode::have_depth_data_ [protected] |
Definition at line 1512 of file vs_grasp.cpp.
ros::ServiceClient VisualServoNode::i_client_ [protected] |
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.
bool VisualServoNode::is_detected_ [protected] |
Definition at line 1577 of file vs_grasp.cpp.
bool VisualServoNode::is_gripper_initialized_ [protected] |
Definition at line 1554 of file vs_grasp.cpp.
image_transport::ImageTransport VisualServoNode::it_ [protected] |
Definition at line 1499 of file vs_grasp.cpp.
int VisualServoNode::jacobian_type_ [protected] |
Definition at line 1533 of file vs_grasp.cpp.
cv::Mat VisualServoNode::K [protected] |
Definition at line 1552 of file vs_grasp.cpp.
VisualServoClient* VisualServoNode::l_vs_client_ [protected] |
Definition at line 437 of file vs_pose.cpp.
double VisualServoNode::min_contour_size_ [protected] |
Definition at line 1530 of file vs_grasp.cpp.
ros::NodeHandle VisualServoNode::n_ [protected] |
Definition at line 1493 of file vs_grasp.cpp.
ros::NodeHandle VisualServoNode::n_private_ [protected] |
Definition at line 1494 of file vs_grasp.cpp.
int VisualServoNode::num_downsamples_ [protected] |
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.
ros::ServiceClient VisualServoNode::p_client_ [protected] |
Definition at line 1563 of file vs_grasp.cpp.
unsigned int VisualServoNode::PHASE [protected] |
Definition at line 1542 of file vs_grasp.cpp.
bool VisualServoNode::place_detection_ [protected] |
Definition at line 1578 of file vs_grasp.cpp.
double VisualServoNode::place_z_velocity_ [protected] |
Definition at line 1536 of file vs_grasp.cpp.
tabletop_pushing::ProtoObjects VisualServoNode::po_ [protected] |
Definition at line 1585 of file vs_grasp.cpp.
double VisualServoNode::pose_servo_z_offset_ [protected] |
Definition at line 1535 of file vs_grasp.cpp.
VisualServoClient* VisualServoNode::r_vs_client_ [protected] |
Definition at line 438 of file vs_pose.cpp.
ReleaseClient* VisualServoNode::release_client_ [protected] |
Definition at line 1569 of file vs_grasp.cpp.
message_filters::Synchronizer< MySyncPolicy > VisualServoNode::sync_ [protected] |
Definition at line 1498 of file vs_grasp.cpp.
double VisualServoNode::tape1_offset_x_ [protected] |
Definition at line 1537 of file vs_grasp.cpp.
double VisualServoNode::tape1_offset_y_ [protected] |
Definition at line 1538 of file vs_grasp.cpp.
double VisualServoNode::tape1_offset_z_ [protected] |
Definition at line 1539 of file vs_grasp.cpp.
std::vector<VSXYZ> VisualServoNode::tape_features_ [protected] |
Definition at line 1549 of file vs_grasp.cpp.
PoseStamped VisualServoNode::tape_features_p_ [protected] |
Definition at line 1550 of file vs_grasp.cpp.
int VisualServoNode::target_hue_threshold_ [protected] |
Definition at line 1524 of file vs_grasp.cpp.
int VisualServoNode::target_hue_value_ [protected] |
Definition at line 1523 of file vs_grasp.cpp.
std::vector< cv::Point > VisualServoNode::temp_draw_ [protected] |
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.
int VisualServoNode::tracker_count_ [protected] |
Definition at line 1520 of file vs_grasp.cpp.
ros::ServiceClient VisualServoNode::v_client_ [protected] |
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.
double VisualServoNode::vs_err_term_threshold_ [protected] |
Definition at line 1534 of file vs_grasp.cpp.
std::string VisualServoNode::workspace_frame_ [protected] |
Definition at line 1515 of file vs_grasp.cpp.