Public Member Functions | |
| GraspAdjustActionServer (char *argv[]) | |
| Default contructor. | |
Private Types | |
| typedef pr2_grasp_adjust::EstimateConfig | Config |
Private Member Functions | |
| void | dynamicCallback (Config &new_config, uint32_t id) |
| Callback for setting algorithm params, such as weights, through dynamic reconfigure. | |
| void | executeCB (const pr2_grasp_adjust::GraspAdjustGoalConstPtr &goal) |
| bool | graspAdjustCallback (pr2_grasp_adjust::GraspAdjust::Request &req, pr2_grasp_adjust::GraspAdjust::Response &res) |
| Service callback for the grasp adjust service. | |
| void | prepareCloud (pcl::PointCloud< pcl::PointXYZ > cloud_in, pcl::PointCloud< PointT > &cloud) |
| void | setupGraspPlanning (object_manipulation_msgs::GraspPlanning::Request &req, pcl::PointCloud< PointT > &cloud) |
| Find normals for the input cluster and generate the pcl::PointCloud. | |
Private Attributes | |
| std::string | action_name_ |
| actionlib::SimpleActionServer < pr2_grasp_adjust::GraspAdjustAction > | as_ |
| tf::TransformBroadcaster | broadcaster_ |
| sensor_msgs::PointCloud2 | cloud_msg_ |
| dynamic_reconfigure::Server < Config >::CallbackType | dyn_cb |
| dynamic_reconfigure::Server < Config > | dyn_srv |
| GraspAdjust | grasp_adjust_ |
| std::string | input_topic_ |
| tf::TransformListener | listener_ |
| ros::NodeHandle | nh_ |
| ros::NodeHandle | nh_pvt_ |
| ros::Time | now_ |
| std::string | output_topic_ |
| ros::Publisher | pub_cloud_ |
| ros::Publisher | pub_cloud_roi_ |
| ros::Publisher | pub_marker_ |
| ros::Publisher | pub_marker_array_ |
| geometry_msgs::PoseStamped | seed_ps_ |
| ros::Subscriber | sub_as_ |
Definition at line 103 of file grasp_adjust_action_server.cpp.
typedef pr2_grasp_adjust::EstimateConfig GraspAdjustActionServer::Config [private] |
Definition at line 132 of file grasp_adjust_action_server.cpp.
| GraspAdjustActionServer::GraspAdjustActionServer | ( | char * | argv[] | ) | [inline] |
Default contructor.
Definition at line 143 of file grasp_adjust_action_server.cpp.
| void GraspAdjustActionServer::dynamicCallback | ( | Config & | new_config, | |
| uint32_t | id | |||
| ) | [inline, private] |
Callback for setting algorithm params, such as weights, through dynamic reconfigure.
Definition at line 338 of file grasp_adjust_action_server.cpp.
| void GraspAdjustActionServer::executeCB | ( | const pr2_grasp_adjust::GraspAdjustGoalConstPtr & | goal | ) | [inline, private] |
Definition at line 185 of file grasp_adjust_action_server.cpp.
| bool GraspAdjustActionServer::graspAdjustCallback | ( | pr2_grasp_adjust::GraspAdjust::Request & | req, | |
| pr2_grasp_adjust::GraspAdjust::Response & | res | |||
| ) | [inline, private] |
Service callback for the grasp adjust service.
| req | The GraspAdjust service request | |
| res | The GraspAdjust response |
Definition at line 274 of file grasp_adjust_action_server.cpp.
| void GraspAdjustActionServer::prepareCloud | ( | pcl::PointCloud< pcl::PointXYZ > | cloud_in, | |
| pcl::PointCloud< PointT > & | cloud | |||
| ) | [inline, private] |
Definition at line 305 of file grasp_adjust_action_server.cpp.
| void GraspAdjustActionServer::setupGraspPlanning | ( | object_manipulation_msgs::GraspPlanning::Request & | req, | |
| pcl::PointCloud< PointT > & | cloud | |||
| ) | [inline, private] |
Find normals for the input cluster and generate the pcl::PointCloud.
| req | The GraspAdjust service request | |
| cloud | Where to put the result |
Definition at line 291 of file grasp_adjust_action_server.cpp.
std::string GraspAdjustActionServer::action_name_ [private] |
Definition at line 126 of file grasp_adjust_action_server.cpp.
actionlib::SimpleActionServer<pr2_grasp_adjust::GraspAdjustAction> GraspAdjustActionServer::as_ [private] |
Definition at line 122 of file grasp_adjust_action_server.cpp.
tf::TransformBroadcaster GraspAdjustActionServer::broadcaster_ [private] |
Definition at line 113 of file grasp_adjust_action_server.cpp.
sensor_msgs::PointCloud2 GraspAdjustActionServer::cloud_msg_ [private] |
Definition at line 115 of file grasp_adjust_action_server.cpp.
dynamic_reconfigure::Server<Config>::CallbackType GraspAdjustActionServer::dyn_cb [private] |
Definition at line 134 of file grasp_adjust_action_server.cpp.
dynamic_reconfigure::Server<Config> GraspAdjustActionServer::dyn_srv [private] |
Definition at line 133 of file grasp_adjust_action_server.cpp.
Definition at line 120 of file grasp_adjust_action_server.cpp.
std::string GraspAdjustActionServer::input_topic_ [private] |
Definition at line 109 of file grasp_adjust_action_server.cpp.
tf::TransformListener GraspAdjustActionServer::listener_ [private] |
Definition at line 112 of file grasp_adjust_action_server.cpp.
ros::NodeHandle GraspAdjustActionServer::nh_ [private] |
Definition at line 105 of file grasp_adjust_action_server.cpp.
ros::NodeHandle GraspAdjustActionServer::nh_pvt_ [private] |
Definition at line 105 of file grasp_adjust_action_server.cpp.
ros::Time GraspAdjustActionServer::now_ [private] |
Definition at line 118 of file grasp_adjust_action_server.cpp.
std::string GraspAdjustActionServer::output_topic_ [private] |
Definition at line 110 of file grasp_adjust_action_server.cpp.
ros::Publisher GraspAdjustActionServer::pub_cloud_ [private] |
Definition at line 107 of file grasp_adjust_action_server.cpp.
ros::Publisher GraspAdjustActionServer::pub_cloud_roi_ [private] |
Definition at line 107 of file grasp_adjust_action_server.cpp.
ros::Publisher GraspAdjustActionServer::pub_marker_ [private] |
Definition at line 107 of file grasp_adjust_action_server.cpp.
ros::Publisher GraspAdjustActionServer::pub_marker_array_ [private] |
Definition at line 107 of file grasp_adjust_action_server.cpp.
geometry_msgs::PoseStamped GraspAdjustActionServer::seed_ps_ [private] |
Definition at line 116 of file grasp_adjust_action_server.cpp.
ros::Subscriber GraspAdjustActionServer::sub_as_ [private] |
Definition at line 106 of file grasp_adjust_action_server.cpp.