#include <CParam.h>
Public Member Functions | |
CParam () | |
void | createTF (std::string header, std::string child) |
void | init_parameter (CParam &Param, LSParam &laserParam, float height_max, float height_min) |
~CParam () | |
Public Attributes | |
double | cam_AOV_h |
double | cam_AOV_v |
float * | cam_cos_h |
float * | cam_cos_v |
double | cam_focal_length_x |
double | cam_focal_length_y |
std::string | cam_frame_id |
int | cam_image_height |
int | cam_image_width |
int * | cam_index |
float * | cam_max_distances |
float * | cam_min_distances |
double | cam_offset |
double | cam_pitch |
float * | cam_sin_v |
double | cam_yaw |
geometry_msgs::TransformStamped * | m_tf |
CParam::CParam | ( | ) |
Definition at line 41 of file CParam.cpp.
CParam::~CParam | ( | ) |
Definition at line 44 of file CParam.cpp.
void CParam::createTF | ( | std::string | header, |
std::string | child | ||
) |
Definition at line 54 of file CParam.cpp.
void CParam::init_parameter | ( | CParam & | Param, |
LSParam & | laserParam, | ||
float | height_max, | ||
float | height_min | ||
) |
Definition at line 83 of file CParam.cpp.
geometry_msgs::TransformStamped* iav_depthimage_to_laserscan::CParam::m_tf |