#include <robot_finder.h>
|
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...
|
|
Definition at line 27 of file robot_finder.h.
◆ RobotFinder()
robot_calibration::RobotFinder::RobotFinder |
( |
| ) |
|
◆ ~RobotFinder()
virtual robot_calibration::RobotFinder::~RobotFinder |
( |
| ) |
|
|
virtualdefault |
◆ 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
-
msg | The 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
-
name | The name of this finder. |
nh | The 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.
◆ max_robot_x_
double robot_calibration::RobotFinder::max_robot_x_ |
|
protected |
◆ max_robot_y_
double robot_calibration::RobotFinder::max_robot_y_ |
|
protected |
◆ max_robot_z_
double robot_calibration::RobotFinder::max_robot_z_ |
|
protected |
◆ min_robot_x_
double robot_calibration::RobotFinder::min_robot_x_ |
|
protected |
◆ min_robot_y_
double robot_calibration::RobotFinder::min_robot_y_ |
|
protected |
◆ min_robot_z_
double robot_calibration::RobotFinder::min_robot_z_ |
|
protected |
◆ robot_publisher_
◆ robot_sensor_name_
std::string robot_calibration::RobotFinder::robot_sensor_name_ |
|
protected |
The documentation for this class was generated from the following files: