IRI ROS Specific Algorithm Class. More...
#include <bow_object_detector_alg_node.h>
IRI ROS Specific Algorithm Class.
Definition at line 70 of file bow_object_detector_alg_node.h.
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.
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.
void BowObjectDetectorAlgNode::detectGraspPoint | ( | ) | [private] |
Definition at line 351 of file bow_object_detector_alg_node.cpp.
void BowObjectDetectorAlgNode::get_grasping_pointGetFeedbackCallback | ( | iri_bow_object_detector::GetGraspingPointFeedbackPtr & | feedback | ) | [private] |
Definition at line 251 of file bow_object_detector_alg_node.cpp.
void BowObjectDetectorAlgNode::get_grasping_pointGetResultCallback | ( | iri_bow_object_detector::GetGraspingPointResultPtr & | result | ) | [private] |
Definition at line 235 of file bow_object_detector_alg_node.cpp.
bool BowObjectDetectorAlgNode::get_grasping_pointHasSucceedCallback | ( | void | ) | [private] |
Definition at line 223 of file bow_object_detector_alg_node.cpp.
bool BowObjectDetectorAlgNode::get_grasping_pointIsFinishedCallback | ( | void | ) | [private] |
Definition at line 211 of file bow_object_detector_alg_node.cpp.
void BowObjectDetectorAlgNode::get_grasping_pointStartCallback | ( | const iri_bow_object_detector::GetGraspingPointGoalConstPtr & | goal | ) | [private] |
Definition at line 188 of file bow_object_detector_alg_node.cpp.
void BowObjectDetectorAlgNode::get_grasping_pointStopCallback | ( | void | ) | [private] |
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.
config | an object with new configuration from all algorithm parameters defined in the config file. |
level | integer 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.
void BowObjectDetectorAlgNode::training | ( | ) | [private] |
Definition at line 399 of file bow_object_detector_alg_node.cpp.
Definition at line 100 of file bow_object_detector_alg_node.h.
Definition at line 101 of file bow_object_detector_alg_node.h.
CEvent BowObjectDetectorAlgNode::EventImageMaskReady [private] |
Definition at line 117 of file bow_object_detector_alg_node.h.
CEvent BowObjectDetectorAlgNode::EventPointCloudReady [private] |
Definition at line 117 of file bow_object_detector_alg_node.h.
CEvent BowObjectDetectorAlgNode::EventWrinkledMapReady [private] |
Definition at line 117 of file bow_object_detector_alg_node.h.
Definition at line 128 of file bow_object_detector_alg_node.h.
IriActionServer<iri_bow_object_detector::GetGraspingPointAction> BowObjectDetectorAlgNode::get_grasping_point_aserver_ [private] |
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.
normal_descriptor_node::ndesc_pc::ConstPtr BowObjectDetectorAlgNode::last_normal_descriptor_ [private] |
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.
CMutex BowObjectDetectorAlgNode::mask_image_in_mutex_ [private] |
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.
CMutex BowObjectDetectorAlgNode::pointcloud_in_mutex_ [private] |
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.
iri_perception_msgs::PclToDescriptorSet BowObjectDetectorAlgNode::pointcloud_to_descriptorset_srv_ [private] |
Definition at line 91 of file bow_object_detector_alg_node.h.
Definition at line 98 of file bow_object_detector_alg_node.h.
iri_bow_object_detector::RefineGraspPoint BowObjectDetectorAlgNode::select_grasp_point_srv_ [private] |
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.