Public Member Functions | Public Attributes
industrial_extrinsic_cal::ROSRuntimeUtils Class Reference

#include <runtime_utils.h>

List of all members.

Public Member Functions

tf::Transform pblockToPose (industrial_extrinsic_cal::P_BLOCK &optimized_input)
 function to convert CalibrationJob P_BLOCK to a pose which can be broadcasted as a transform
 ROSRuntimeUtils ()
 constructor
bool store_tf_broadcasters (std::string &package_name, std::string &file_name)
 saved final calibrated transforms as launch file
 ~ROSRuntimeUtils ()
 Default destructor.

Public Attributes

std::vector
< tf::TransformBroadcaster > 
broadcasters_
 set of broadcasters for transform of camera(s) and target(s)
std::vector
< industrial_extrinsic_cal::P_BLOCK
calibrated_extrinsics_
 set of calibrated extrinsics of camera(s)
std::vector< tf::Transform > calibrated_transforms_
 set of resultant calibrated transform of camera(s)
std::string caljob_file_
 file containing Calibration Job definition parameters
std::string camera_file_
 file containing camera definition parameters
std::vector< std::string > camera_intermediate_frame_
 name of camera frame which links camera optical frame to reference frame
std::vector< tf::StampedTransform > camera_internal_transforms_
 set of transforms of from camera intermediate to camera optical frames
std::vector< std::string > camera_optical_frame_
 name of camera frame in which observations were made
std::vector
< industrial_extrinsic_cal::P_BLOCK
initial_extrinsics_
 set of initial extrinsics of camera(s)
std::vector< tf::Transform > initial_transforms_
 set of initial transform of camera(s)
tf::TransformListener listener_
 set of listeners for transform from camera intermediate to camera optical frames
std::vector< tf::StampedTransform > points_to_world_transforms_
 set of transforms of from camera intermediate to camera optical frames
std::string target_file_
 file containing target definition parameters
std::vector< std::string > target_frame_
 name frame for target points
std::vector
< industrial_extrinsic_cal::P_BLOCK
target_poses_
 set of calibrated extrinsics of target(s)
std::vector< tf::Transform > target_transforms_
 set target transforms
std::string world_frame_
 name of overall reference frame

Detailed Description

Definition at line 37 of file runtime_utils.h.


Constructor & Destructor Documentation

constructor

Definition at line 44 of file runtime_utils.h.

Default destructor.

Definition at line 50 of file runtime_utils.h.


Member Function Documentation

function to convert CalibrationJob P_BLOCK to a pose which can be broadcasted as a transform

Parameters:
optimized_input
Returns:
Tranform to be published/broadcasted

Definition at line 25 of file runtime_utils.cpp.

bool industrial_extrinsic_cal::ROSRuntimeUtils::store_tf_broadcasters ( std::string &  package_name,
std::string &  file_name 
)

saved final calibrated transforms as launch file

Parameters:
package_namedirectory to package path
file_namename to save under package path
Returns:
true if tf's successfully written to file

Definition at line 57 of file runtime_utils.cpp.


Member Data Documentation

std::vector<tf::TransformBroadcaster> industrial_extrinsic_cal::ROSRuntimeUtils::broadcasters_

set of broadcasters for transform of camera(s) and target(s)

Definition at line 137 of file runtime_utils.h.

set of calibrated extrinsics of camera(s)

Definition at line 106 of file runtime_utils.h.

set of resultant calibrated transform of camera(s)

Definition at line 121 of file runtime_utils.h.

file containing Calibration Job definition parameters

Definition at line 80 of file runtime_utils.h.

file containing camera definition parameters

Definition at line 72 of file runtime_utils.h.

name of camera frame which links camera optical frame to reference frame

Definition at line 96 of file runtime_utils.h.

set of transforms of from camera intermediate to camera optical frames

Definition at line 125 of file runtime_utils.h.

name of camera frame in which observations were made

Definition at line 92 of file runtime_utils.h.

set of initial extrinsics of camera(s)

Definition at line 102 of file runtime_utils.h.

set of initial transform of camera(s)

Definition at line 117 of file runtime_utils.h.

set of listeners for transform from camera intermediate to camera optical frames

Definition at line 141 of file runtime_utils.h.

set of transforms of from camera intermediate to camera optical frames

Definition at line 129 of file runtime_utils.h.

file containing target definition parameters

Definition at line 76 of file runtime_utils.h.

name frame for target points

Definition at line 88 of file runtime_utils.h.

set of calibrated extrinsics of target(s)

Definition at line 110 of file runtime_utils.h.

set target transforms

Definition at line 133 of file runtime_utils.h.

name of overall reference frame

Definition at line 84 of file runtime_utils.h.


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


industrial_extrinsic_cal
Author(s): Chris Lewis
autogenerated on Wed Aug 26 2015 12:00:27