GraspAdjustServer Class Reference

List of all members.

Public Member Functions

 GraspAdjustServer (char *argv[])
 Default contructor.

Private Types

typedef
pr2_grasp_adjust::EstimateConfig 
Config
typedef
pr2_grasp_adjust::DebugConfig 
Debug

Private Member Functions

void cloud_callback (const sensor_msgs::PointCloud2ConstPtr &input)
 Callback for receiving a point cloud.
void debugCallback (Debug &new_config, uint32_t id)
 Callback for setting debug gripper poses through dynamic reconfigure.
void dynamicCallback (Config &new_config, uint32_t id)
 Callback for setting algorithm params, such as weights, through dynamic reconfigure.
geometry_msgs::PoseStamped generateRelativePose (geometry_msgs::PoseStamped original_pose, double roll, double pitch, double yaw, double xdist, double ydist, double zdist)
bool graspAdjustCallback (pr2_grasp_adjust::GraspAdjust::Request &req, pr2_grasp_adjust::GraspAdjust::Response &res)
 Service callback for the grasp adjust service.
bool graspEvaluateCallback (object_manipulation_msgs::GraspPlanning::Request &req, object_manipulation_msgs::GraspPlanning::Response &res)
 Service callback for the grasp evaluate service.
bool graspPlanCallback (object_manipulation_msgs::GraspPlanning::Request &req, object_manipulation_msgs::GraspPlanning::Response &res)
 Service callback for the grasp planning service.
void setupGraspPlanning (object_manipulation_msgs::GraspPlanning::Request &req, pcl::PointCloud< PointT > &cloud)
 Find normals for the input cluster and generate the pcl::PointCloud.
void timerCallback ()
 The timer callback allows you to run the adjustment algorithm continuously.

Private Attributes

ros::ServiceServer adjust_srv_
object_manipulator::ServiceWrapper
< object_manipulation_msgs::FindClusterBoundingBox > 
bounding_box_client_
tf::TransformBroadcaster broadcaster_
dynamic_reconfigure::Server
< Debug >::CallbackType 
debug_cb
dynamic_reconfigure::Server
< Debug
debug_srv
dynamic_reconfigure::Server
< Config >::CallbackType 
dyn_cb
dynamic_reconfigure::Server
< Config
dyn_srv
ros::ServiceServer evaluate_srv_
bool got_first_cloud_
GraspAdjust grasp_adjust_
std::string input_topic_
pcl::PointCloud< PointTlast_cloud_
tf::TransformListener listener_
ros::NodeHandle nh_
ros::NodeHandle nh_pvt_
ros::Time now_
std::string output_topic_
ros::ServiceServer plan_srv_
ros::Publisher pub_cloud_
ros::Publisher pub_cloud_debug_2
ros::Publisher pub_cloud_roi_
ros::Publisher pub_marker_
ros::Publisher pub_marker_array_
ros::Subscriber sub_cloud_
std::ofstream train_file_
bool training_
ros::Timer update_timer_

Detailed Description

Definition at line 99 of file grasp_adjust_server.cpp.


Member Typedef Documentation

typedef pr2_grasp_adjust::EstimateConfig GraspAdjustServer::Config [private]

Definition at line 124 of file grasp_adjust_server.cpp.

typedef pr2_grasp_adjust::DebugConfig GraspAdjustServer::Debug [private]

Definition at line 128 of file grasp_adjust_server.cpp.


Constructor & Destructor Documentation

GraspAdjustServer::GraspAdjustServer ( char *  argv[]  )  [inline]

Default contructor.

Definition at line 143 of file grasp_adjust_server.cpp.


Member Function Documentation

void GraspAdjustServer::cloud_callback ( const sensor_msgs::PointCloud2ConstPtr &  input  )  [inline, private]

Callback for receiving a point cloud.

Definition at line 526 of file grasp_adjust_server.cpp.

void GraspAdjustServer::debugCallback ( Debug new_config,
uint32_t  id 
) [inline, private]

Callback for setting debug gripper poses through dynamic reconfigure.

Definition at line 584 of file grasp_adjust_server.cpp.

void GraspAdjustServer::dynamicCallback ( Config new_config,
uint32_t  id 
) [inline, private]

Callback for setting algorithm params, such as weights, through dynamic reconfigure.

Definition at line 546 of file grasp_adjust_server.cpp.

geometry_msgs::PoseStamped GraspAdjustServer::generateRelativePose ( geometry_msgs::PoseStamped  original_pose,
double  roll,
double  pitch,
double  yaw,
double  xdist,
double  ydist,
double  zdist 
) [inline, private]

Generate a new PoseStamped message whose pose is relative to original_pose

Definition at line 315 of file grasp_adjust_server.cpp.

bool GraspAdjustServer::graspAdjustCallback ( pr2_grasp_adjust::GraspAdjust::Request &  req,
pr2_grasp_adjust::GraspAdjust::Response &  res 
) [inline, private]

Service callback for the grasp adjust service.

Parameters:
req The GraspAdjust service request
res The GraspAdjust response

Definition at line 261 of file grasp_adjust_server.cpp.

bool GraspAdjustServer::graspEvaluateCallback ( object_manipulation_msgs::GraspPlanning::Request &  req,
object_manipulation_msgs::GraspPlanning::Response &  res 
) [inline, private]

Service callback for the grasp evaluate service.

Parameters:
req The GraspPlanning service request
res The GraspPlanning response

Definition at line 455 of file grasp_adjust_server.cpp.

bool GraspAdjustServer::graspPlanCallback ( object_manipulation_msgs::GraspPlanning::Request &  req,
object_manipulation_msgs::GraspPlanning::Response &  res 
) [inline, private]

Service callback for the grasp planning service.

Parameters:
req The GraspPlanning service request
res The GraspPlanning response

Definition at line 334 of file grasp_adjust_server.cpp.

void GraspAdjustServer::setupGraspPlanning ( object_manipulation_msgs::GraspPlanning::Request &  req,
pcl::PointCloud< PointT > &  cloud 
) [inline, private]

Find normals for the input cluster and generate the pcl::PointCloud.

Parameters:
req The GraspAdjust service request
cloud Where to put the result

Definition at line 278 of file grasp_adjust_server.cpp.

void GraspAdjustServer::timerCallback (  )  [inline, private]

The timer callback allows you to run the adjustment algorithm continuously.

Definition at line 208 of file grasp_adjust_server.cpp.


Member Data Documentation

ros::ServiceServer GraspAdjustServer::adjust_srv_ [private]

Definition at line 108 of file grasp_adjust_server.cpp.

object_manipulator::ServiceWrapper<object_manipulation_msgs::FindClusterBoundingBox> GraspAdjustServer::bounding_box_client_ [private]

Definition at line 133 of file grasp_adjust_server.cpp.

tf::TransformBroadcaster GraspAdjustServer::broadcaster_ [private]

Definition at line 115 of file grasp_adjust_server.cpp.

dynamic_reconfigure::Server<Debug>::CallbackType GraspAdjustServer::debug_cb [private]

Definition at line 130 of file grasp_adjust_server.cpp.

dynamic_reconfigure::Server<Debug> GraspAdjustServer::debug_srv [private]

Definition at line 129 of file grasp_adjust_server.cpp.

dynamic_reconfigure::Server<Config>::CallbackType GraspAdjustServer::dyn_cb [private]

Definition at line 126 of file grasp_adjust_server.cpp.

dynamic_reconfigure::Server<Config> GraspAdjustServer::dyn_srv [private]

Definition at line 125 of file grasp_adjust_server.cpp.

ros::ServiceServer GraspAdjustServer::evaluate_srv_ [private]

Definition at line 108 of file grasp_adjust_server.cpp.

Definition at line 119 of file grasp_adjust_server.cpp.

Definition at line 121 of file grasp_adjust_server.cpp.

std::string GraspAdjustServer::input_topic_ [private]

Definition at line 111 of file grasp_adjust_server.cpp.

pcl::PointCloud<PointT> GraspAdjustServer::last_cloud_ [private]

Definition at line 101 of file grasp_adjust_server.cpp.

tf::TransformListener GraspAdjustServer::listener_ [private]

Definition at line 114 of file grasp_adjust_server.cpp.

ros::NodeHandle GraspAdjustServer::nh_ [private]

Definition at line 103 of file grasp_adjust_server.cpp.

ros::NodeHandle GraspAdjustServer::nh_pvt_ [private]

Definition at line 103 of file grasp_adjust_server.cpp.

ros::Time GraspAdjustServer::now_ [private]

Definition at line 117 of file grasp_adjust_server.cpp.

std::string GraspAdjustServer::output_topic_ [private]

Definition at line 112 of file grasp_adjust_server.cpp.

ros::ServiceServer GraspAdjustServer::plan_srv_ [private]

Definition at line 108 of file grasp_adjust_server.cpp.

ros::Publisher GraspAdjustServer::pub_cloud_ [private]

Definition at line 105 of file grasp_adjust_server.cpp.

ros::Publisher GraspAdjustServer::pub_cloud_debug_2 [private]

Definition at line 106 of file grasp_adjust_server.cpp.

ros::Publisher GraspAdjustServer::pub_cloud_roi_ [private]

Definition at line 106 of file grasp_adjust_server.cpp.

ros::Publisher GraspAdjustServer::pub_marker_ [private]

Definition at line 105 of file grasp_adjust_server.cpp.

ros::Publisher GraspAdjustServer::pub_marker_array_ [private]

Definition at line 105 of file grasp_adjust_server.cpp.

ros::Subscriber GraspAdjustServer::sub_cloud_ [private]

Definition at line 104 of file grasp_adjust_server.cpp.

std::ofstream GraspAdjustServer::train_file_ [private]

Definition at line 137 of file grasp_adjust_server.cpp.

Definition at line 136 of file grasp_adjust_server.cpp.

ros::Timer GraspAdjustServer::update_timer_ [private]

Definition at line 109 of file grasp_adjust_server.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


pr2_grasp_adjust
Author(s): Adam Leeper
autogenerated on Fri Jan 11 09:53:54 2013