Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
BowObjectDetectorAlgNode Class Reference

IRI ROS Specific Algorithm Class. More...

#include <bow_object_detector_alg_node.h>

Inheritance diagram for BowObjectDetectorAlgNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BowObjectDetectorAlgNode (void)
 Constructor.
 ~BowObjectDetectorAlgNode (void)
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
void mainNodeThread (void)
 main node thread
void node_config_update (Config &config, uint32_t level)
 dynamic reconfigure server callback

Private Member Functions

cv::Mat crop_and_resize (cv::Mat &image)
sensor_msgs::ImagePtr cv_image_to_ros_image (cv::Mat cvimage, std_msgs::Header header)
void detectGraspPoint ()
void get_grasping_pointGetFeedbackCallback (iri_bow_object_detector::GetGraspingPointFeedbackPtr &feedback)
void get_grasping_pointGetResultCallback (iri_bow_object_detector::GetGraspingPointResultPtr &result)
bool get_grasping_pointHasSucceedCallback (void)
bool get_grasping_pointIsFinishedCallback (void)
void get_grasping_pointStartCallback (const iri_bow_object_detector::GetGraspingPointGoalConstPtr &goal)
void get_grasping_pointStopCallback (void)
void mask_image_in_callback (const sensor_msgs::Image::ConstPtr &msg)
cv::Mat pcl_pointcloud_to_cv_image (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud)
void pointcloud_in_callback (const sensor_msgs::PointCloud2::ConstPtr &msg)
sensor_msgs::Image ros_pointcloud_to_ros_image (sensor_msgs::PointCloud2 ros_cloud)
void save_pcd_to_disk (sensor_msgs::PointCloud2 ros_cloud)
void training ()

Private Attributes

ros::ServiceClient detectObjects_client_
iri_bow_object_detector::GeoVwDetection detectObjects_srv_
CEvent EventImageMaskReady
CEvent EventPointCloudReady
CEvent EventWrinkledMapReady
bool first_pointcloud_
IriActionServer
< iri_bow_object_detector::GetGraspingPointAction
get_grasping_point_aserver_
ros::ServiceClient get_sift_descriptors_client_
iri_sift::DescriptorsFromImage get_sift_descriptors_srv_
ros::ServiceClient get_vws_client_
iri_perception_msgs::DescriptorsToVws get_vws_srv_
ros::ServiceClient getVwSet_client_
iri_sift::GeoVwSetSrv getVwSet_srv_
bool image_mask_ready_
sensor_msgs::Image Image_msg_
ros::Publisher image_out_publisher_
sensor_msgs::Image last_image_
sensor_msgs::Image last_image_mask_
normal_descriptor_node::ndesc_pc::ConstPtr last_normal_descriptor_
sensor_msgs::PointCloud2 last_pointcloud_
iri_perception_msgs::DescriptorSet last_sift_descriptors_
iri_perception_msgs::GeoVwSet last_sift_vw_set_
sensor_msgs::PointCloud2::ConstPtr last_wrinkled_map_
CMutex mask_image_in_mutex_
ros::Subscriber mask_image_in_subscriber_
sensor_msgs::PointCloud2 PointCloud2_msg_
CMutex pointcloud_in_mutex_
ros::Subscriber pointcloud_in_subscriber_
ros::Publisher pointcloud_out_publisher_
bool pointcloud_ready_
ros::ServiceClient pointcloud_to_descriptorset_client_
iri_perception_msgs::PclToDescriptorSet pointcloud_to_descriptorset_srv_
ros::ServiceClient select_grasp_point_client_
iri_bow_object_detector::RefineGraspPoint select_grasp_point_srv_
ros::ServiceClient set_background_image_client_
iri_perception_msgs::SetImage set_background_image_srv_
bool solution_ready_
bool wrinkled_map_ready_

Detailed Description

IRI ROS Specific Algorithm Class.

Definition at line 70 of file bow_object_detector_alg_node.h.


Constructor & Destructor Documentation

Constructor.

This constructor initializes specific class attributes and all ROS communications variables to enable message exchange.

Definition at line 3 of file bow_object_detector_alg_node.cpp.

Destructor.

This destructor frees all necessary dynamic memory allocated within this this class.

Definition at line 45 of file bow_object_detector_alg_node.cpp.


Member Function Documentation

void BowObjectDetectorAlgNode::addNodeDiagnostics ( void  ) [protected, virtual]

node add diagnostics

In this abstract function additional ROS diagnostics applied to the specific algorithms may be added.

Implements algorithm_base::IriBaseAlgorithm< BowObjectDetectorAlgorithm >.

Definition at line 268 of file bow_object_detector_alg_node.cpp.

cv::Mat BowObjectDetectorAlgNode::crop_and_resize ( cv::Mat &  image) [private]

Definition at line 334 of file bow_object_detector_alg_node.cpp.

sensor_msgs::ImagePtr BowObjectDetectorAlgNode::cv_image_to_ros_image ( cv::Mat  cvimage,
std_msgs::Header  header 
) [private]

Definition at line 342 of file bow_object_detector_alg_node.cpp.

Definition at line 351 of file bow_object_detector_alg_node.cpp.

Definition at line 251 of file bow_object_detector_alg_node.cpp.

Definition at line 235 of file bow_object_detector_alg_node.cpp.

Definition at line 223 of file bow_object_detector_alg_node.cpp.

Definition at line 211 of file bow_object_detector_alg_node.cpp.

Definition at line 188 of file bow_object_detector_alg_node.cpp.

Definition at line 204 of file bow_object_detector_alg_node.cpp.

void BowObjectDetectorAlgNode::mainNodeThread ( void  ) [protected, virtual]

main node thread

This is the main thread node function. Code written here will be executed in every node loop while the algorithm is on running state. Loop frequency can be tuned by modifying loop_rate attribute.

Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.

Implements algorithm_base::IriBaseAlgorithm< BowObjectDetectorAlgorithm >.

Definition at line 50 of file bow_object_detector_alg_node.cpp.

void BowObjectDetectorAlgNode::mask_image_in_callback ( const sensor_msgs::Image::ConstPtr &  msg) [private]

Definition at line 136 of file bow_object_detector_alg_node.cpp.

void BowObjectDetectorAlgNode::node_config_update ( Config config,
uint32_t  level 
) [protected, virtual]

dynamic reconfigure server callback

This method is called whenever a new configuration is received through the dynamic reconfigure. The derivated generic algorithm class must implement it.

Parameters:
configan object with new configuration from all algorithm parameters defined in the config file.
levelinteger referring the level in which the configuration has been changed.

Implements algorithm_base::IriBaseAlgorithm< BowObjectDetectorAlgorithm >.

Definition at line 261 of file bow_object_detector_alg_node.cpp.

cv::Mat BowObjectDetectorAlgNode::pcl_pointcloud_to_cv_image ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  cloud) [private]

Definition at line 300 of file bow_object_detector_alg_node.cpp.

void BowObjectDetectorAlgNode::pointcloud_in_callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [private]

Definition at line 155 of file bow_object_detector_alg_node.cpp.

sensor_msgs::Image BowObjectDetectorAlgNode::ros_pointcloud_to_ros_image ( sensor_msgs::PointCloud2  ros_cloud) [private]

Definition at line 280 of file bow_object_detector_alg_node.cpp.

void BowObjectDetectorAlgNode::save_pcd_to_disk ( sensor_msgs::PointCloud2  ros_cloud) [private]

Definition at line 292 of file bow_object_detector_alg_node.cpp.

Definition at line 399 of file bow_object_detector_alg_node.cpp.


Member Data Documentation

Definition at line 100 of file bow_object_detector_alg_node.h.

Definition at line 101 of file bow_object_detector_alg_node.h.

Definition at line 117 of file bow_object_detector_alg_node.h.

Definition at line 117 of file bow_object_detector_alg_node.h.

Definition at line 117 of file bow_object_detector_alg_node.h.

Definition at line 128 of file bow_object_detector_alg_node.h.

Definition at line 106 of file bow_object_detector_alg_node.h.

Definition at line 94 of file bow_object_detector_alg_node.h.

Definition at line 95 of file bow_object_detector_alg_node.h.

Definition at line 92 of file bow_object_detector_alg_node.h.

Definition at line 93 of file bow_object_detector_alg_node.h.

Definition at line 102 of file bow_object_detector_alg_node.h.

Definition at line 103 of file bow_object_detector_alg_node.h.

Definition at line 130 of file bow_object_detector_alg_node.h.

sensor_msgs::Image BowObjectDetectorAlgNode::Image_msg_ [private]

Definition at line 75 of file bow_object_detector_alg_node.h.

Definition at line 74 of file bow_object_detector_alg_node.h.

sensor_msgs::Image BowObjectDetectorAlgNode::last_image_ [private]

Definition at line 123 of file bow_object_detector_alg_node.h.

sensor_msgs::Image BowObjectDetectorAlgNode::last_image_mask_ [private]

Definition at line 122 of file bow_object_detector_alg_node.h.

Definition at line 126 of file bow_object_detector_alg_node.h.

sensor_msgs::PointCloud2 BowObjectDetectorAlgNode::last_pointcloud_ [private]

Definition at line 121 of file bow_object_detector_alg_node.h.

Definition at line 119 of file bow_object_detector_alg_node.h.

Definition at line 120 of file bow_object_detector_alg_node.h.

sensor_msgs::PointCloud2::ConstPtr BowObjectDetectorAlgNode::last_wrinkled_map_ [private]

Definition at line 125 of file bow_object_detector_alg_node.h.

Definition at line 82 of file bow_object_detector_alg_node.h.

Definition at line 80 of file bow_object_detector_alg_node.h.

sensor_msgs::PointCloud2 BowObjectDetectorAlgNode::PointCloud2_msg_ [private]

Definition at line 77 of file bow_object_detector_alg_node.h.

Definition at line 85 of file bow_object_detector_alg_node.h.

Definition at line 83 of file bow_object_detector_alg_node.h.

Definition at line 76 of file bow_object_detector_alg_node.h.

Definition at line 129 of file bow_object_detector_alg_node.h.

Definition at line 90 of file bow_object_detector_alg_node.h.

Definition at line 91 of file bow_object_detector_alg_node.h.

Definition at line 98 of file bow_object_detector_alg_node.h.

Definition at line 99 of file bow_object_detector_alg_node.h.

Definition at line 96 of file bow_object_detector_alg_node.h.

Definition at line 97 of file bow_object_detector_alg_node.h.

Definition at line 132 of file bow_object_detector_alg_node.h.

Definition at line 131 of file bow_object_detector_alg_node.h.


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


iri_bow_object_detector
Author(s): dmartinez
autogenerated on Fri Dec 6 2013 22:45:46