Public Member Functions | Protected Member Functions | Protected Attributes
camera_pose_calibration::CameraPoseCalibrationNode Class Reference

#include <node.hpp>

List of all members.

Public Member Functions

 CameraPoseCalibrationNode ()

Protected Member Functions

bool calibrate (sensor_msgs::Image const &sensor_msgs_image, sensor_msgs::PointCloud2 const &sensor_msgs_cloud, std::string const &tag_frame, std::string const &target_frame, double const &point_cloud_scale_x, double const &point_cloud_scale_y, camera_pose_calibration::PatternParameters const &pattern, geometry_msgs::Transform &transform)
 Calibrates and publishes the tf and debug information.
visualization_msgs::Marker createCalibrationPlaneMarker (pcl::PointCloud< pcl::PointXYZ >::ConstPtr points, uint8_t pattern_width, uint8_t pattern_height)
 Create a marker for the detected calibration plane.
bool onCalibrateCall (camera_pose_calibration::CalibrateCall::Request &req, camera_pose_calibration::CalibrateCall::Response &res)
 Calibrates the camera given all the information in the request.
bool onCalibrateFile (camera_pose_calibration::CalibrateFile::Request &req, camera_pose_calibration::CalibrateFile::Response &res)
 Calibrates the camera given the image and point cloud by a ROS topic, and all other information in the request.
bool onCalibrateTopic (camera_pose_calibration::CalibrateTopic::Request &req, camera_pose_calibration::CalibrateTopic::Response &res)
 Calibrates the camera given the image and point cloud by a ROS topic, and all other information in the request.
void onTfTimeout (ros::TimerEvent const &)
 Called when the calibrated TF transforms should be republished.
void parseInput ()
 Parses ROS parameters and calls the calibration service.

Protected Attributes

ros::ServiceServer calibrate_server_call
 Service server for calibration with all data in the service call.
ros::ServiceServer calibrate_server_file
 Service server for calibration with image and cloud from file.
ros::ServiceServer calibrate_server_topic
 Service server for calibration with image and cloud from topics.
bool calibrated
 Determines if we have calibrated (and thus should publish the transform).
ros::Publisher calibration_plane_marker_publisher
 Publishes a marker for showing the plane of the calibration points.
tf::StampedTransform calibration_transform
 The found calibration transformation.
ros::Publisher cloud_publisher
 Publishes the original pointcloud.
image_transport::Publisher detected_pattern_publisher
 Image transport publisher for publishing the detected pattern.
image_transport::ImageTransport image_transport
 Image transport object used for publishing images.
ros::NodeHandle node_handle
 Node handle.
ros::Publisher projected_source_cloud_publisher
 Publishes the detected pattern but projected on a fitted plane.
double publish_rate
 Rate with which to publish transforms.
bool publish_transform
 Determines whether to publish the transform over tf.
ros::Publisher source_cloud_publisher
 Publishes the detected pattern from the source cloud.
ros::Publisher target_cloud_publisher
 Publishes the expected (generated) pattern.
ros::Timer tf_timer
 Timer to periodically republish TF transforms.
tf::TransformBroadcaster transform_broadcaster
 Publishes tf transforms.
tf::TransformListener transform_listener
 Listens to transforms from tf to transform calibration from the correct target to the camera.
ros::Publisher transformed_target_cloud_publisher
 Publishes the expected pattern transformed using the found calibration transform.

Detailed Description

Definition at line 35 of file node.hpp.


Constructor & Destructor Documentation

Definition at line 54 of file node.cpp.


Member Function Documentation

bool camera_pose_calibration::CameraPoseCalibrationNode::calibrate ( sensor_msgs::Image const &  sensor_msgs_image,
sensor_msgs::PointCloud2 const &  sensor_msgs_cloud,
std::string const &  tag_frame,
std::string const &  target_frame,
double const &  point_cloud_scale_x,
double const &  point_cloud_scale_y,
camera_pose_calibration::PatternParameters const &  pattern,
geometry_msgs::Transform &  transform 
) [protected]

Calibrates and publishes the tf and debug information.

Definition at line 139 of file node.cpp.

visualization_msgs::Marker camera_pose_calibration::CameraPoseCalibrationNode::createCalibrationPlaneMarker ( pcl::PointCloud< pcl::PointXYZ >::ConstPtr  points,
uint8_t  pattern_width,
uint8_t  pattern_height 
) [protected]

Create a marker for the detected calibration plane.

Definition at line 80 of file node.cpp.

bool camera_pose_calibration::CameraPoseCalibrationNode::onCalibrateCall ( camera_pose_calibration::CalibrateCall::Request &  req,
camera_pose_calibration::CalibrateCall::Response &  res 
) [protected]

Calibrates the camera given all the information in the request.

Calibrates the camera given the information in the request.

Definition at line 359 of file node.cpp.

bool camera_pose_calibration::CameraPoseCalibrationNode::onCalibrateFile ( camera_pose_calibration::CalibrateFile::Request &  req,
camera_pose_calibration::CalibrateFile::Response &  res 
) [protected]

Calibrates the camera given the image and point cloud by a ROS topic, and all other information in the request.

Definition at line 263 of file node.cpp.

bool camera_pose_calibration::CameraPoseCalibrationNode::onCalibrateTopic ( camera_pose_calibration::CalibrateTopic::Request &  req,
camera_pose_calibration::CalibrateTopic::Response &  res 
) [protected]

Calibrates the camera given the image and point cloud by a ROS topic, and all other information in the request.

Definition at line 309 of file node.cpp.

Called when the calibrated TF transforms should be republished.

Definition at line 132 of file node.cpp.

Parses ROS parameters and calls the calibration service.


Member Data Documentation

Service server for calibration with all data in the service call.

Definition at line 74 of file node.hpp.

Service server for calibration with image and cloud from file.

Definition at line 80 of file node.hpp.

Service server for calibration with image and cloud from topics.

Definition at line 77 of file node.hpp.

Determines if we have calibrated (and thus should publish the transform).

Definition at line 95 of file node.hpp.

Publishes a marker for showing the plane of the calibration points.

Definition at line 71 of file node.hpp.

The found calibration transformation.

Definition at line 86 of file node.hpp.

Publishes the original pointcloud.

Definition at line 56 of file node.hpp.

Image transport publisher for publishing the detected pattern.

Definition at line 47 of file node.hpp.

Image transport object used for publishing images.

Definition at line 44 of file node.hpp.

Node handle.

Definition at line 41 of file node.hpp.

Publishes the detected pattern but projected on a fitted plane.

Definition at line 68 of file node.hpp.

Rate with which to publish transforms.

Definition at line 92 of file node.hpp.

Determines whether to publish the transform over tf.

Definition at line 89 of file node.hpp.

Publishes the detected pattern from the source cloud.

Definition at line 65 of file node.hpp.

Publishes the expected (generated) pattern.

Definition at line 59 of file node.hpp.

Timer to periodically republish TF transforms.

Definition at line 83 of file node.hpp.

Publishes tf transforms.

Definition at line 53 of file node.hpp.

Listens to transforms from tf to transform calibration from the correct target to the camera.

Definition at line 50 of file node.hpp.

Publishes the expected pattern transformed using the found calibration transform.

Definition at line 62 of file node.hpp.


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


camera_pose_calibration
Author(s): Hans Gaiser , Jeff van Egmond , Maarten de Vries , Mihai Morariu , Ronald Ensing
autogenerated on Thu Jun 6 2019 20:34:08