Public Member Functions | Protected Member Functions | Protected Attributes
VisualServo Class Reference

List of all members.

Public Member Functions

std::vector< VSXYZCVPointToVSXYZ (XYZPointCloud cloud, cv::Mat depth_frame, std::vector< cv::Point > in)
VSXYZ CVPointToVSXYZ (XYZPointCloud cloud, cv::Mat depth_frame, cv::Point in)
visual_servo::VisualServoTwist getTwist (std::vector< PoseStamped > goal, std::vector< PoseStamped > gripper)
visual_servo::VisualServoTwist getTwist (std::vector< PoseStamped > goal, std::vector< PoseStamped > gripper, int mode)
visual_servo::VisualServoTwist getTwist (std::vector< VSXYZ > goal, std::vector< VSXYZ > gripper, cv::Mat error)
visual_servo::VisualServoTwist getTwist (std::vector< VSXYZ > goal, std::vector< VSXYZ > gripper)
std::vector< VSXYZPoint3DToVSXYZ (std::vector< pcl::PointXYZ > in, shared_ptr< tf::TransformListener > tf_)
VSXYZ point3DToVSXYZ (pcl::PointXYZ in, shared_ptr< tf::TransformListener > tf_)
void printVSXYZ (VSXYZ i)
cv::Point projectPointIntoImage (pcl::PointXYZ cur_point_pcl, std::string point_frame, std::string target_frame, shared_ptr< tf::TransformListener > tf_)
void setCamInfo (sensor_msgs::CameraInfo cam_info)
bool setDesiredInteractionMatrix (std::vector< VSXYZ > &pts)
 VisualServo (int jacobian_type)
PoseStamped VSXYZToPoseStamped (VSXYZ v)

Protected Member Functions

visual_servo::VisualServoTwist computeTwist (cv::Mat error_mat, cv::Mat im, std::string optical_frame)
float diffAngle (float a0, float a1)
cv::Mat getMeterInteractionMatrix (std::vector< PoseStamped > &pts)
cv::Mat getMeterInteractionMatrix (std::vector< VSXYZ > &pts)
float getZValue (cv::Mat depth_frame, int x, int y)
visual_servo::VisualServoTwist IBVSTwist (std::vector< VSXYZ > desired, std::vector< VSXYZ > pts)
visual_servo::VisualServoTwist IBVSTwist (std::vector< VSXYZ > desired, std::vector< VSXYZ > pts, cv::Mat error_mat)
visual_servo::VisualServoTwist IBVSTwist (std::vector< PoseStamped > desired, std::vector< PoseStamped > pts)
cv::Mat MatDiffAngle (cv::Mat m0, cv::Mat m1)
visual_servo::VisualServoTwist PBVSTwist (cv::Mat error_pose, cv::Mat error_rot)
visual_servo::VisualServoTwist PBVSTwist (std::vector< PoseStamped > desired, std::vector< PoseStamped > pts)
void printMatrix (cv::Mat_< double > in)
cv::Mat projectImageMatToPoint (cv::Mat in)
cv::Mat projectImagePointToPoint (cv::Point in)
cv::Point projectPointIntoImage (PointStamped cur_point, std::string target_frame, shared_ptr< tf::TransformListener > tf_)
cv::Mat pseudoInverse (cv::Mat im)
visual_servo::VisualServoTwist transformVelocity (cv::Mat in)

Protected Attributes

sensor_msgs::CameraInfo cam_info_
cv::Mat desired_jacobian_
bool desired_jacobian_set_
double gain_rot_
double gain_vel_
int jacobian_type_
cv::Mat K
tf::TransformListener listener_
ros::NodeHandle n_
ros::NodeHandle n_private_
std::string optical_frame_
double term_threshold_
tf::StampedTransform transform
std::string workspace_frame_

Detailed Description

We are taping robot hand with three blue painter's tape and use those three features to do the image-based visual servoing Uses Kinect as image sensor and provide a twist computation service

Definition at line 188 of file visual_servo.cpp.


Constructor & Destructor Documentation

VisualServo::VisualServo ( int  jacobian_type) [inline]

Definition at line 191 of file visual_servo.cpp.


Member Function Documentation

visual_servo::VisualServoTwist VisualServo::computeTwist ( cv::Mat  error_mat,
cv::Mat  im,
std::string  optical_frame 
) [inline, protected]

Definition at line 528 of file visual_servo.cpp.

std::vector<VSXYZ> VisualServo::CVPointToVSXYZ ( XYZPointCloud  cloud,
cv::Mat  depth_frame,
std::vector< cv::Point in 
) [inline]

Definition at line 308 of file visual_servo.cpp.

VSXYZ VisualServo::CVPointToVSXYZ ( XYZPointCloud  cloud,
cv::Mat  depth_frame,
cv::Point  in 
) [inline]

Definition at line 318 of file visual_servo.cpp.

float VisualServo::diffAngle ( float  a0,
float  a1 
) [inline, protected]

Definition at line 455 of file visual_servo.cpp.

cv::Mat VisualServo::getMeterInteractionMatrix ( std::vector< PoseStamped > &  pts) [inline, protected]

get the interaction matrix

Parameters:
depth_frameNeed the depth information from Kinect for Z
ptsVector of feature points
Returns:
Return the computed interaction Matrix (6 by 6)

Definition at line 572 of file visual_servo.cpp.

cv::Mat VisualServo::getMeterInteractionMatrix ( std::vector< VSXYZ > &  pts) [inline, protected]

Definition at line 602 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::getTwist ( std::vector< PoseStamped >  goal,
std::vector< PoseStamped >  gripper 
) [inline]

Definition at line 222 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::getTwist ( std::vector< PoseStamped >  goal,
std::vector< PoseStamped >  gripper,
int  mode 
) [inline]

Definition at line 228 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::getTwist ( std::vector< VSXYZ goal,
std::vector< VSXYZ gripper,
cv::Mat  error 
) [inline]

Definition at line 239 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::getTwist ( std::vector< VSXYZ goal,
std::vector< VSXYZ gripper 
) [inline]

Definition at line 244 of file visual_servo.cpp.

float VisualServo::getZValue ( cv::Mat  depth_frame,
int  x,
int  y 
) [inline, protected]

Definition at line 711 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::IBVSTwist ( std::vector< VSXYZ desired,
std::vector< VSXYZ pts 
) [inline, protected]

Definition at line 467 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::IBVSTwist ( std::vector< VSXYZ desired,
std::vector< VSXYZ pts,
cv::Mat  error_mat 
) [inline, protected]

Definition at line 487 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::IBVSTwist ( std::vector< PoseStamped >  desired,
std::vector< PoseStamped >  pts 
) [inline, protected]

Definition at line 502 of file visual_servo.cpp.

cv::Mat VisualServo::MatDiffAngle ( cv::Mat  m0,
cv::Mat  m1 
) [inline, protected]

Definition at line 440 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::PBVSTwist ( cv::Mat  error_pose,
cv::Mat  error_rot 
) [inline, protected]

Definition at line 370 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::PBVSTwist ( std::vector< PoseStamped >  desired,
std::vector< PoseStamped >  pts 
) [inline, protected]

this is for another approach of PBVS According to Chaumette 2006 v = -lambda( (c*t0 - ct0) + [ct0]x theta u) form [ct0]x first cv::Mat ctox = cv::Mat::zeros(3,3,CV_32F); cur position ctox.at<float>(0,1) = -cpos.z; ctox.at<float>(0,2) = cpos.y; ctox.at<float>(1,0) = cpos.z; ctox.at<float>(2,0) = -cpos.y; ctox.at<float>(1,2) = -cpos.x; ctox.at<float>(2,1) = cpos.x;

cv::Mat velpos = -gain_vel_*((mgpos - mcpos) + ctox*(mgrot-mcrot)); cv::Mat velrot = -gain_rot_*(mgrot - mcrot);

Definition at line 377 of file visual_servo.cpp.

std::vector<VSXYZ> VisualServo::Point3DToVSXYZ ( std::vector< pcl::PointXYZ >  in,
shared_ptr< tf::TransformListener tf_ 
) [inline]

Definition at line 270 of file visual_servo.cpp.

VSXYZ VisualServo::point3DToVSXYZ ( pcl::PointXYZ  in,
shared_ptr< tf::TransformListener tf_ 
) [inline]

Definition at line 280 of file visual_servo.cpp.

void VisualServo::printMatrix ( cv::Mat_< double >  in) [inline, protected]

Definition at line 762 of file visual_servo.cpp.

void VisualServo::printVSXYZ ( VSXYZ  i) [inline]

Definition at line 345 of file visual_servo.cpp.

cv::Mat VisualServo::projectImageMatToPoint ( cv::Mat  in) [inline, protected]

transforms a cv::Mat in pixels to meter using the inverse Image Intrinsic K

Parameters:
incv::Mat input to be transformed
Returns:
returns meter in cv::Mat

Definition at line 665 of file visual_servo.cpp.

cv::Mat VisualServo::projectImagePointToPoint ( cv::Point  in) [inline, protected]

transforms a point in pixels to meter using the inverse of image intrinsic K

Parameters:
ina point to be transformed
Returns:
returns meter value of the point in cv::Mat

Definition at line 641 of file visual_servo.cpp.

cv::Point VisualServo::projectPointIntoImage ( pcl::PointXYZ  cur_point_pcl,
std::string  point_frame,
std::string  target_frame,
shared_ptr< tf::TransformListener tf_ 
) [inline]

Definition at line 334 of file visual_servo.cpp.

cv::Point VisualServo::projectPointIntoImage ( PointStamped  cur_point,
std::string  target_frame,
shared_ptr< tf::TransformListener tf_ 
) [inline, protected]

Definition at line 682 of file visual_servo.cpp.

cv::Mat VisualServo::pseudoInverse ( cv::Mat  im) [inline, protected]

Definition at line 561 of file visual_servo.cpp.

void VisualServo::setCamInfo ( sensor_msgs::CameraInfo  cam_info) [inline]

Definition at line 217 of file visual_servo.cpp.

Definition at line 249 of file visual_servo.cpp.

visual_servo::VisualServoTwist VisualServo::transformVelocity ( cv::Mat  in) [inline, protected]

Definition at line 738 of file visual_servo.cpp.

PoseStamped VisualServo::VSXYZToPoseStamped ( VSXYZ  v) [inline]

Definition at line 298 of file visual_servo.cpp.


Member Data Documentation

sensor_msgs::CameraInfo VisualServo::cam_info_ [protected]

Definition at line 368 of file visual_servo.cpp.

cv::Mat VisualServo::desired_jacobian_ [protected]

Definition at line 366 of file visual_servo.cpp.

Definition at line 365 of file visual_servo.cpp.

double VisualServo::gain_rot_ [protected]

Definition at line 363 of file visual_servo.cpp.

double VisualServo::gain_vel_ [protected]

Definition at line 362 of file visual_servo.cpp.

int VisualServo::jacobian_type_ [protected]

Definition at line 361 of file visual_servo.cpp.

cv::Mat VisualServo::K [protected]

Definition at line 367 of file visual_servo.cpp.

Definition at line 359 of file visual_servo.cpp.

Definition at line 352 of file visual_servo.cpp.

Definition at line 353 of file visual_servo.cpp.

std::string VisualServo::optical_frame_ [protected]

Definition at line 356 of file visual_servo.cpp.

double VisualServo::term_threshold_ [protected]

Definition at line 364 of file visual_servo.cpp.

Definition at line 357 of file visual_servo.cpp.

std::string VisualServo::workspace_frame_ [protected]

Definition at line 355 of file visual_servo.cpp.


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


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