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

IRI ROS Specific Algorithm Class. More...

#include <door_cloud_alg_node.h>

Inheritance diagram for DoorCloudAlgNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 DoorCloudAlgNode (void)
 Constructor.
 ~DoorCloudAlgNode (void)
 Destructor.

Protected Member Functions

void addNodeDiagnostics (void)
 node add diagnostics
visualization_msgs::Marker ArrowMarker (std_msgs::Header header, geometry_msgs::Pose pose, int alpha, int color, const char arrow_tag[])
 Arrow Marker.
pcl::PointCloud< pcl::PointXYZ > filterCloud (pcl::PointCloud< pcl::PointXYZ > raw_cloud, float Lowx, float Uppx, float Lowy, float Uppy, float Lowz, float Uppz, bool negative_limits)
 volume filter for a point cloud
void mainNodeThread (void)
 main node thread
void node_config_update (Config &config, uint32_t level)
 dynamic reconfigure server callback
boost::tuple< pcl::PointCloud
< pcl::PointXYZ >
, pcl::PointIndices::Ptr,
pcl::ModelCoefficients::Ptr
planeFit (pcl::PointCloud< pcl::PointXYZ > raw_cloud)
 RANSAC plane fit.
geometry_msgs::Quaternion quaternionFromVectors (tf::Vector3 vector_1, tf::Vector3 vector_2)
 Quaterion from vectors.

Private Member Functions

void door_action_start_callback (const std_msgs::Int8::ConstPtr &msg)
void door_centroid_callback (const geometry_msgs::PoseStamped::ConstPtr &msg)
void handle_location_callback (const geometry_msgs::PoseStamped::ConstPtr &msg)
void points_callback (const sensor_msgs::PointCloud2::ConstPtr &msg)

Private Attributes

int captured_closed
int captured_open
sensor_msgs::PointCloud2 closed_door_cloud
ros::Publisher closed_door_cloud_publisher_
ros::Publisher closed_door_marker_publisher_
pcl::PointCloud< pcl::PointXYZ > cloud
pcl::PointCloud< pcl::PointXYZ > cloud_filtered
pcl::PointCloud< pcl::PointXYZ > cloud_filtered_left
pcl::PointCloud< pcl::PointXYZ > cloud_filtered_right
pcl::PointCloud< pcl::PointXYZ > cloud_filtered_top
pcl::PointCloud< pcl::PointXYZ > cloud_plane
CMutex door_action_start_mutex_
ros::Subscriber door_action_start_subscriber_
CMutex door_centroid_mutex_
ros::Publisher door_centroid_publisher_
ros::Subscriber door_centroid_subscriber_
ros::Publisher door_handle_publisher_
boost::tuple< pcl::PointCloud
< pcl::PointXYZ >
, pcl::PointIndices::Ptr,
pcl::ModelCoefficients::Ptr
door_plane
CMutex handle_location_mutex_
ros::Subscriber handle_location_subscriber_
float lower_x
float lower_y
float lower_z
visualization_msgs::Marker marker
visualization_msgs::Marker Marker_msg_
bool no_simulator
sensor_msgs::PointCloud2 open_door_cloud
ros::Publisher open_door_cloud_publisher_
ros::Publisher open_door_marker_publisher_
geometry_msgs::Quaternion orient
sensor_msgs::PointCloud2 PointCloud2_msg_
CMutex points_mutex_
ros::Subscriber points_subscriber_
geometry_msgs::PoseStamped poses
geometry_msgs::PoseStamped PoseStamped_msg_
int start
std::string tf_original_frame
float upper_x
float upper_y
float upper_z
float w_closed
float w_open
float x_closed
float x_left
float x_open
float x_right
float y_closed
float y_open
float y_top
float z_closed
float z_open

Detailed Description

IRI ROS Specific Algorithm Class.

Definition at line 64 of file door_cloud_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 door_cloud_alg_node.cpp.

Destructor.

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

Definition at line 44 of file door_cloud_alg_node.cpp.


Member Function Documentation

void DoorCloudAlgNode::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< DoorCloudAlgorithm >.

Definition at line 412 of file door_cloud_alg_node.cpp.

visualization_msgs::Marker DoorCloudAlgNode::ArrowMarker ( std_msgs::Header  header,
geometry_msgs::Pose  pose,
int  alpha,
int  color,
const char  arrow_tag[] 
) [protected]

Arrow Marker.

Construct an arrow marker for plane orientation visualization

Definition at line 507 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::door_action_start_callback ( const std_msgs::Int8::ConstPtr &  msg) [private]

Definition at line 67 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::door_centroid_callback ( const geometry_msgs::PoseStamped::ConstPtr &  msg) [private]

Definition at line 94 of file door_cloud_alg_node.cpp.

pcl::PointCloud< pcl::PointXYZ > DoorCloudAlgNode::filterCloud ( pcl::PointCloud< pcl::PointXYZ >  raw_cloud,
float  Lowx,
float  Uppx,
float  Lowy,
float  Uppy,
float  Lowz,
float  Uppz,
bool  negative_limits 
) [protected]

volume filter for a point cloud

Removes points outisde x and z limits

Definition at line 423 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::handle_location_callback ( const geometry_msgs::PoseStamped::ConstPtr &  msg) [private]

Definition at line 120 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::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< DoorCloudAlgorithm >.

Definition at line 49 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::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< DoorCloudAlgorithm >.

Definition at line 403 of file door_cloud_alg_node.cpp.

boost::tuple< pcl::PointCloud< pcl::PointXYZ >, pcl::PointIndices::Ptr, pcl::ModelCoefficients::Ptr > DoorCloudAlgNode::planeFit ( pcl::PointCloud< pcl::PointXYZ >  raw_cloud) [protected]

RANSAC plane fit.

Returns plane coefficients, inliers and fitted plane point cloud in a tuple

Definition at line 458 of file door_cloud_alg_node.cpp.

void DoorCloudAlgNode::points_callback ( const sensor_msgs::PointCloud2::ConstPtr &  msg) [private]

Definition at line 144 of file door_cloud_alg_node.cpp.

geometry_msgs::Quaternion DoorCloudAlgNode::quaternionFromVectors ( tf::Vector3  vector_1,
tf::Vector3  vector_2 
) [protected]

Quaterion from vectors.

Return rotation quaternion between two unit vectors

Definition at line 491 of file door_cloud_alg_node.cpp.


Member Data Documentation

Definition at line 109 of file door_cloud_alg_node.h.

Definition at line 108 of file door_cloud_alg_node.h.

sensor_msgs::PointCloud2 DoorCloudAlgNode::closed_door_cloud [private]

Definition at line 139 of file door_cloud_alg_node.h.

Definition at line 74 of file door_cloud_alg_node.h.

Definition at line 76 of file door_cloud_alg_node.h.

pcl::PointCloud<pcl::PointXYZ> DoorCloudAlgNode::cloud [private]

Definition at line 129 of file door_cloud_alg_node.h.

Definition at line 130 of file door_cloud_alg_node.h.

Definition at line 131 of file door_cloud_alg_node.h.

Definition at line 132 of file door_cloud_alg_node.h.

Definition at line 133 of file door_cloud_alg_node.h.

Definition at line 134 of file door_cloud_alg_node.h.

Definition at line 85 of file door_cloud_alg_node.h.

Definition at line 83 of file door_cloud_alg_node.h.

Definition at line 91 of file door_cloud_alg_node.h.

Definition at line 72 of file door_cloud_alg_node.h.

Definition at line 89 of file door_cloud_alg_node.h.

Definition at line 78 of file door_cloud_alg_node.h.

Definition at line 135 of file door_cloud_alg_node.h.

Definition at line 94 of file door_cloud_alg_node.h.

Definition at line 92 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::lower_x [private]

Definition at line 122 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::lower_y [private]

Definition at line 123 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::lower_z [private]

Definition at line 124 of file door_cloud_alg_node.h.

visualization_msgs::Marker DoorCloudAlgNode::marker [private]

Definition at line 140 of file door_cloud_alg_node.h.

visualization_msgs::Marker DoorCloudAlgNode::Marker_msg_ [private]

Definition at line 71 of file door_cloud_alg_node.h.

Definition at line 105 of file door_cloud_alg_node.h.

sensor_msgs::PointCloud2 DoorCloudAlgNode::open_door_cloud [private]

Definition at line 138 of file door_cloud_alg_node.h.

Definition at line 68 of file door_cloud_alg_node.h.

Definition at line 70 of file door_cloud_alg_node.h.

geometry_msgs::Quaternion DoorCloudAlgNode::orient [private]

Definition at line 137 of file door_cloud_alg_node.h.

sensor_msgs::PointCloud2 DoorCloudAlgNode::PointCloud2_msg_ [private]

Definition at line 69 of file door_cloud_alg_node.h.

Definition at line 88 of file door_cloud_alg_node.h.

Definition at line 86 of file door_cloud_alg_node.h.

geometry_msgs::PoseStamped DoorCloudAlgNode::poses [private]

Definition at line 136 of file door_cloud_alg_node.h.

geometry_msgs::PoseStamped DoorCloudAlgNode::PoseStamped_msg_ [private]

Definition at line 73 of file door_cloud_alg_node.h.

int DoorCloudAlgNode::start [private]

Definition at line 110 of file door_cloud_alg_node.h.

std::string DoorCloudAlgNode::tf_original_frame [private]

Definition at line 128 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::upper_x [private]

Definition at line 125 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::upper_y [private]

Definition at line 126 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::upper_z [private]

Definition at line 127 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::w_closed [private]

Definition at line 121 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::w_open [private]

Definition at line 117 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::x_closed [private]

Definition at line 118 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::x_left [private]

Definition at line 111 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::x_open [private]

Definition at line 113 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::x_right [private]

Definition at line 112 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::y_closed [private]

Definition at line 119 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::y_open [private]

Definition at line 115 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::y_top [private]

Definition at line 114 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::z_closed [private]

Definition at line 120 of file door_cloud_alg_node.h.

float DoorCloudAlgNode::z_open [private]

Definition at line 116 of file door_cloud_alg_node.h.


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


iri_door_detector
Author(s): Jose Rodriguez
autogenerated on Fri Dec 6 2013 23:57:17