Go to the documentation of this file.
20 #ifndef ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
21 #define ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
24 #include <sensor_msgs/CameraInfo.h>
25 #include <robot_calibration_msgs/CalibrationData.h>
26 #include <robot_calibration_msgs/ExtendedCameraInfo.h>
40 std::string topic_name;
41 n.
param<std::string>(
"camera_info_topic", topic_name,
"/head_camera/depth/camera_info");
49 std::string driver_name;
50 n.
param<std::string>(
"camera_driver", driver_name,
"/head_camera/driver");
54 ROS_ERROR(
"%s is not set, are drivers running?",driver_name.c_str());
71 ROS_WARN(
"CameraInfo receive timed out.");
77 robot_calibration_msgs::ExtendedCameraInfo info;
79 info.parameters.resize(2);
80 info.parameters[0].name =
"z_offset_mm";
82 info.parameters[1].name =
"z_scaling";
105 #endif // ROBOT_CALIBRATION_CAPTURE_DEPTH_CAMERA_H
void cameraInfoCallback(const sensor_msgs::CameraInfo::Ptr camera_info)
bool init(ros::NodeHandle &n)
bool getParam(const std::string &key, bool &b) const
Base class for a feature finder.
ROSCPP_DECL void spinOnce()
virtual ~DepthCameraInfoManager()
ros::Subscriber camera_info_subscriber_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Calibration code lives under this namespace.
T param(const std::string ¶m_name, const T &default_val) const
sensor_msgs::CameraInfo::Ptr camera_info_ptr_
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01