
Additional Inherited Members | |
Public Member Functions inherited from depth_sensor_pose::DepthSensorPose | |
| DepthSensorPose ()=default | |
| DepthSensorPose (const DepthSensorPose &)=delete | |
| void | estimateParams (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
| sensor_msgs::ImageConstPtr | getDbgImage () const |
| bool | getPublishDepthEnable () const |
| getPublishDepthEnable More... | |
| float | getSensorMountHeight () const |
| float | getSensorTiltAngle () const |
| DepthSensorPose & | operator= (const DepthSensorPose &)=delete |
| void | setCamModelUpdate (const bool u) |
| setCamModelUpdate More... | |
| void | setDepthImgStepCol (const int step) |
| setDepthImgStepCol More... | |
| void | setDepthImgStepRow (const int step) |
| setDepthImgStepRow More... | |
| void | setGroundMaxPoints (const unsigned u) |
| void | setPublishDepthEnable (const bool enable) |
| setPublishDepthEnable More... | |
| void | setRangeLimits (const float rmin, const float rmax) |
| void | setRansacDistanceThresh (const float u) |
| void | setRansacMaxIter (const unsigned u) |
| void | setReconfParamsUpdated (bool updated) |
| setReconfParamsUpdated More... | |
| void | setSensorMountHeightMax (const float height) |
| setSensorMountHeight sets the height of sensor mount (in meters) from ground More... | |
| void | setSensorMountHeightMin (const float height) |
| setSensorMountHeight sets the height of sensor mount (in meters) from ground More... | |
| void | setSensorTiltAngleMax (const float angle) |
| setSensorTiltAngle sets the sensor tilt angle (in degrees) More... | |
| void | setSensorTiltAngleMin (const float angle) |
| setSensorTiltAngle sets the sensor tilt angle (in degrees) More... | |
| void | setUsedDepthHeight (const unsigned height) |
| setUsedDepthHeight More... | |
| ~DepthSensorPose ()=default | |
Protected Member Functions inherited from depth_sensor_pose::DepthSensorPose | |
| double | angleBetweenRays (const cv::Point3d &ray1, const cv::Point3d &ray2) const |
| void | calcDeltaAngleForImgRows (double vertical_fov) |
| void | calcGroundDistancesForImgRows (double mount_height, double tilt_angle, std::vector< double > &distances) |
| Calculates distances to ground for every row of depth image. More... | |
| void | fieldOfView (double &min, double &max, double x1, double y1, double xc, double yc, double x2, double y2) |
| template<typename T > | |
| void | getGroundPoints (const sensor_msgs::ImageConstPtr &depth_msg, pcl::PointCloud< pcl::PointXYZ >::Ptr &points, std::list< std::pair< unsigned, unsigned >> &points_indices) |
| double | lengthOfVector (const cv::Point3d &vec) const |
| sensor_msgs::ImagePtr | prepareDbgImage (const sensor_msgs::ImageConstPtr &depth_msg, const std::list< std::pair< unsigned, unsigned >> &ground_points_indices) |
| void | sensorPoseCalibration (const sensor_msgs::ImageConstPtr &depth_msg, double &tilt_angle, double &height) |
Definition at line 7 of file depth_sensor_pose_test.cpp.