Public Member Functions | Protected Attributes | List of all members
robot_calibration::RobotFinder Class Reference

#include <robot_finder.h>

Inheritance diagram for robot_calibration::RobotFinder:
Inheritance graph
[legend]

Public Member Functions

virtual bool find (robot_calibration_msgs::CalibrationData *msg)
 Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in. More...
 
virtual bool init (const std::string &name, ros::NodeHandle &n)
 Initialize the feature finder. More...
 
 RobotFinder ()
 
virtual ~RobotFinder ()=default
 
- Public Member Functions inherited from robot_calibration::PlaneFinder
 PlaneFinder ()
 
virtual ~PlaneFinder ()=default
 
- Public Member Functions inherited from robot_calibration::FeatureFinder
 FeatureFinder ()
 
std::string getName ()
 Get the name of this feature finder. More...
 
virtual ~FeatureFinder ()
 

Protected Attributes

double max_robot_x_
 
double max_robot_y_
 
double max_robot_z_
 
double min_robot_x_
 
double min_robot_y_
 
double min_robot_z_
 
ros::Publisher robot_publisher_
 
std::string robot_sensor_name_
 
- Protected Attributes inherited from robot_calibration::PlaneFinder
sensor_msgs::PointCloud2 cloud_
 
double cos_normal_angle_
 
DepthCameraInfoManager depth_camera_manager_
 
Eigen::Vector3d desired_normal_
 
double initial_sampling_distance_
 
double max_x_
 
double max_y_
 
double max_z_
 
double min_x_
 
double min_y_
 
double min_z_
 
bool output_debug_
 
std::string plane_sensor_name_
 
double plane_tolerance_
 
int points_max_
 
ros::Publisher publisher_
 
int ransac_iterations_
 
int ransac_points_
 
ros::Subscriber subscriber_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
std::string transform_frame_
 
bool waiting_
 

Additional Inherited Members

- Protected Member Functions inherited from robot_calibration::PlaneFinder
virtual void cameraCallback (const sensor_msgs::PointCloud2 &cloud)
 ROS callback - updates cloud_ and resets waiting_ to false. More...
 
virtual void extractObservation (const std::string &sensor_name, const sensor_msgs::PointCloud2 &cloud, robot_calibration_msgs::CalibrationData *msg, ros::Publisher *publisher)
 Extract points from a cloud into a calibration message. More...
 
virtual sensor_msgs::PointCloud2 extractPlane (sensor_msgs::PointCloud2 &cloud)
 Extract a plane from the point cloud. More...
 
virtual void removeInvalidPoints (sensor_msgs::PointCloud2 &cloud, double min_x, double max_x, double min_y, double max_y, double min_z, double max_z)
 Remove invalid points from a cloud. More...
 
virtual bool waitForCloud ()
 Wait until a new cloud has arrived. More...
 

Detailed Description

Definition at line 27 of file robot_finder.h.

Constructor & Destructor Documentation

◆ RobotFinder()

robot_calibration::RobotFinder::RobotFinder ( )

Definition at line 36 of file robot_finder.cpp.

◆ ~RobotFinder()

virtual robot_calibration::RobotFinder::~RobotFinder ( )
virtualdefault

Member Function Documentation

◆ find()

bool robot_calibration::RobotFinder::find ( robot_calibration_msgs::CalibrationData *  msg)
virtual

Once the robot has been moved into the proper position and settled, this function will be called. It should add any new observations to the msg passed in.

Parameters
msgThe message to which observations should be added.
Returns
True if feature finder succeeded in finding the features and adding them to the observation list. False otherwise.

Reimplemented from robot_calibration::PlaneFinder.

Definition at line 64 of file robot_finder.cpp.

◆ init()

bool robot_calibration::RobotFinder::init ( const std::string &  name,
ros::NodeHandle nh 
)
virtual

Initialize the feature finder.

Parameters
nameThe name of this finder.
nhThe nodehandle to use when loading feature finder configuration data.
Returns
True/False if the feature finder was able to be initialized

Reimplemented from robot_calibration::PlaneFinder.

Definition at line 41 of file robot_finder.cpp.

Member Data Documentation

◆ max_robot_x_

double robot_calibration::RobotFinder::max_robot_x_
protected

Definition at line 43 of file robot_finder.h.

◆ max_robot_y_

double robot_calibration::RobotFinder::max_robot_y_
protected

Definition at line 45 of file robot_finder.h.

◆ max_robot_z_

double robot_calibration::RobotFinder::max_robot_z_
protected

Definition at line 47 of file robot_finder.h.

◆ min_robot_x_

double robot_calibration::RobotFinder::min_robot_x_
protected

Definition at line 42 of file robot_finder.h.

◆ min_robot_y_

double robot_calibration::RobotFinder::min_robot_y_
protected

Definition at line 44 of file robot_finder.h.

◆ min_robot_z_

double robot_calibration::RobotFinder::min_robot_z_
protected

Definition at line 46 of file robot_finder.h.

◆ robot_publisher_

ros::Publisher robot_calibration::RobotFinder::robot_publisher_
protected

Definition at line 40 of file robot_finder.h.

◆ robot_sensor_name_

std::string robot_calibration::RobotFinder::robot_sensor_name_
protected

Definition at line 37 of file robot_finder.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01