$search

FieldOfView Class Reference

List of all members.

Public Member Functions

void computeFieldOfView ()
 calculates coordinate system from parameters
void dynReconfCallback (cob_3d_mapping_common::field_of_viewConfig &config, uint32_t level)
 FieldOfView ()
visualization_msgs::Marker generateMarker (std::string &target_frame, ros::Time &stamp)
 generates markers to visualize field of view vectors
void setSensorFoV_hor (double val)
 callback for dynamic reconfigure
void setSensorFoV_ver (double val)
void setSensorMaxRange (double val)
bool srvCallback_GetFieldOfView (cob_3d_mapping_msgs::GetFieldOfView::Request &req, cob_3d_mapping_msgs::GetFieldOfView::Response &res)
 request to recalculate the field of view
void transformFOV (ros::Time stamp, std::string target_frame)
 uses global transformation (of the robot) to recalculate the field of view
 ~FieldOfView ()

Protected Attributes

std::string camera_frame_
 maximum range of sensor
dynamic_reconfigure::Server
< cob_3d_mapping_common::field_of_viewConfig > 
config_server_
ros::Publisher fov_marker_pub_
ros::ServiceServer get_fov_srv_
boost::mutex m_mutex
ros::NodeHandle n_
tf::Point n_down_
 field of view vector
tf::Point n_down_t_
 transformed field of view vector
tf::Point n_left_
 field of view vector
tf::Point n_left_t_
 transformed field of view vector
tf::Point n_origin_t_
 transformed field of view vector
tf::Point n_right_
 field of view vector
tf::Point n_right_t_
 transformed field of view vector
tf::Point n_up_
 part of view frustum
tf::Point n_up_t_
 field of view vector
ros::Publisher point_cloud_pub_
ros::Subscriber point_cloud_sub_
double sensor_fov_hor_
double sensor_fov_ver_
 horizontal angle of sensor
double sensor_max_range_
 vertical angle of sensor
ros::Time stamp_
TransformListener tf_listener_
Eigen::Vector3d vec_a_
Eigen::Vector3d vec_b_
 part of view frustum
Eigen::Vector3d vec_c_
 part of view frustum
Eigen::Vector3d vec_d_
 part of view frustum

Detailed Description

Definition at line 85 of file field_of_view.cpp.


Constructor & Destructor Documentation

FieldOfView::FieldOfView (  )  [inline]

Definition at line 89 of file field_of_view.cpp.

FieldOfView::~FieldOfView (  )  [inline]

void

Definition at line 105 of file field_of_view.cpp.


Member Function Documentation

void FieldOfView::computeFieldOfView (  )  [inline]

calculates coordinate system from parameters

calculates coordinate system from parameters

Returns:
nothing

cross product b x a

cross product c x d

cross product b x c

cross product d x a

Definition at line 182 of file field_of_view.cpp.

void FieldOfView::dynReconfCallback ( cob_3d_mapping_common::field_of_viewConfig &  config,
uint32_t  level 
) [inline]

Definition at line 110 of file field_of_view.cpp.

visualization_msgs::Marker FieldOfView::generateMarker ( std::string &  target_frame,
ros::Time stamp 
) [inline]

generates markers to visualize field of view vectors

generates markers to visualize field of view vectors

Parameters:
stamp timestamp indicating used frame
target_frame targetframe
Returns:
markers

Definition at line 333 of file field_of_view.cpp.

void FieldOfView::setSensorFoV_hor ( double  val  )  [inline]

callback for dynamic reconfigure

everytime the dynamic reconfiguration changes this function will be called

Parameters:
inst instance of FieldOfView which parameters should be changed
config data of configuration
level bit descriptor which notifies which parameter changed
Returns:
nothing

Definition at line 163 of file field_of_view.cpp.

void FieldOfView::setSensorFoV_ver ( double  val  )  [inline]

Definition at line 167 of file field_of_view.cpp.

void FieldOfView::setSensorMaxRange ( double  val  )  [inline]

Definition at line 171 of file field_of_view.cpp.

bool FieldOfView::srvCallback_GetFieldOfView ( cob_3d_mapping_msgs::GetFieldOfView::Request req,
cob_3d_mapping_msgs::GetFieldOfView::Response res 
) [inline]

request to recalculate the field of view

request to recalculate the field of view

Parameters:
req parameters
res containing field of view vectors
Returns:
nothing

Definition at line 441 of file field_of_view.cpp.

void FieldOfView::transformFOV ( ros::Time  stamp,
std::string  target_frame 
) [inline]

uses global transformation (of the robot) to recalculate the field of view

uses global transformation (of the robot) to recalculate the field of view (all vectors)

Parameters:
stamp timestamp indicating used frame
target_frame targetframe
Returns:
nothing

Definition at line 239 of file field_of_view.cpp.


Member Data Documentation

std::string FieldOfView::camera_frame_ [protected]

maximum range of sensor

Definition at line 477 of file field_of_view.cpp.

dynamic_reconfigure::Server<cob_3d_mapping_common::field_of_viewConfig> FieldOfView::config_server_ [protected]

Definition at line 472 of file field_of_view.cpp.

Definition at line 467 of file field_of_view.cpp.

Definition at line 468 of file field_of_view.cpp.

boost::mutex FieldOfView::m_mutex [protected]

Definition at line 495 of file field_of_view.cpp.

Definition at line 464 of file field_of_view.cpp.

field of view vector

Definition at line 485 of file field_of_view.cpp.

transformed field of view vector

Definition at line 490 of file field_of_view.cpp.

field of view vector

Definition at line 487 of file field_of_view.cpp.

transformed field of view vector

Definition at line 492 of file field_of_view.cpp.

transformed field of view vector

Definition at line 493 of file field_of_view.cpp.

field of view vector

Definition at line 486 of file field_of_view.cpp.

transformed field of view vector

Definition at line 491 of file field_of_view.cpp.

part of view frustum

Definition at line 484 of file field_of_view.cpp.

field of view vector

Definition at line 489 of file field_of_view.cpp.

Definition at line 466 of file field_of_view.cpp.

Definition at line 465 of file field_of_view.cpp.

double FieldOfView::sensor_fov_hor_ [protected]

Definition at line 474 of file field_of_view.cpp.

double FieldOfView::sensor_fov_ver_ [protected]

horizontal angle of sensor

Definition at line 475 of file field_of_view.cpp.

double FieldOfView::sensor_max_range_ [protected]

vertical angle of sensor

Definition at line 476 of file field_of_view.cpp.

Definition at line 469 of file field_of_view.cpp.

Definition at line 471 of file field_of_view.cpp.

Eigen::Vector3d FieldOfView::vec_a_ [protected]

Definition at line 479 of file field_of_view.cpp.

Eigen::Vector3d FieldOfView::vec_b_ [protected]

part of view frustum

Definition at line 480 of file field_of_view.cpp.

Eigen::Vector3d FieldOfView::vec_c_ [protected]

part of view frustum

Definition at line 481 of file field_of_view.cpp.

Eigen::Vector3d FieldOfView::vec_d_ [protected]

part of view frustum

Definition at line 482 of file field_of_view.cpp.


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


cob_3d_mapping_common
Author(s): Georg Arbeiter
autogenerated on Fri Mar 1 15:17:38 2013