The main calibration object. More...
#include <calibration.hpp>
Public Member Functions | |
void | attempt_calibration () |
Attempt to calibrate the cameras. | |
calibration () | |
Creates a calibration object. | |
void | publish_tf () |
Publish known fixed frames of the markers to a global frame and the averages from the AR tracker. | |
Private Member Functions | |
void | marker_cback (const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &msg, int camera) |
AR marker topic callback function. | |
void | write_calibration () |
Write the calibration settings to a URDF file. | |
Private Attributes | |
std::vector< geometry_msgs::Pose > | average_poses_ |
tf::TransformBroadcaster | br |
bool | calibrated_ |
std::string | camera_frame_id_prefix_ |
std::string | fixed_frame_ |
std::vector< geometry_msgs::Pose > | fixed_poses_ |
std::vector< ros::Subscriber > | marker_subs_ |
ros::NodeHandle | nh_ |
int | num_cameras_ |
int | num_samples_ |
ros::NodeHandle | pnh_ |
std::vector< std::vector < geometry_msgs::Pose > > | samples_ |
The main calibration object.
The calibration object subscribes to all necessary topics to calibrate the ceiling cameras.
Definition at line 47 of file calibration.hpp.
Creates a calibration object.
Creates a calibration object that can be used to calibrate a number of ceiling cameras. ROS nodes, services, and publishers are created and maintained within this object.
Definition at line 20 of file calibration.cpp.
void calibration::attempt_calibration | ( | ) |
Attempt to calibrate the cameras.
Attempt to calibrate the cameras. Cameras will calibrate once enough samples have come in.
Definition at line 126 of file calibration.cpp.
void calibration::marker_cback | ( | const ar_track_alvar_msgs::AlvarMarkers::ConstPtr & | msg, |
int | camera | ||
) | [private] |
AR marker topic callback function.
Process and store the incoming AR marker positions from each camera.
msg | the message for the marker topic |
camera | the camera number |
Definition at line 69 of file calibration.cpp.
void calibration::publish_tf | ( | ) |
Publish known fixed frames of the markers to a global frame and the averages from the AR tracker.
Publish known fixed frames of the markers to a global frame and the averages from the AR tracker. This will allow later calculations to these frames.
Definition at line 87 of file calibration.cpp.
void calibration::write_calibration | ( | ) | [private] |
Write the calibration settings to a URDF file.
Writes a file called 'ceiling.urdf.xacro' with the calibration settings.
Definition at line 178 of file calibration.cpp.
std::vector<geometry_msgs::Pose> calibration::average_poses_ [private] |
the known fixed pose of each marker and average from the AR tracker
Definition at line 101 of file calibration.hpp.
tf::TransformBroadcaster calibration::br [private] |
main transform broadcaster
Definition at line 93 of file calibration.hpp.
bool calibration::calibrated_ [private] |
a flag to check if the calibration is complete
Definition at line 91 of file calibration.hpp.
std::string calibration::camera_frame_id_prefix_ [private] |
the fixed frame of the markers and frame of the cameras
Definition at line 98 of file calibration.hpp.
std::string calibration::fixed_frame_ [private] |
Definition at line 98 of file calibration.hpp.
std::vector<geometry_msgs::Pose> calibration::fixed_poses_ [private] |
Definition at line 101 of file calibration.hpp.
std::vector<ros::Subscriber> calibration::marker_subs_ [private] |
the subscriptions to the marker topic
Definition at line 100 of file calibration.hpp.
ros::NodeHandle calibration::nh_ [private] |
Definition at line 95 of file calibration.hpp.
int calibration::num_cameras_ [private] |
Definition at line 97 of file calibration.hpp.
int calibration::num_samples_ [private] |
the number of ceiling cameras and samples to take
Definition at line 97 of file calibration.hpp.
ros::NodeHandle calibration::pnh_ [private] |
a handle for this ROS node and the private node handle
Definition at line 95 of file calibration.hpp.
std::vector<std::vector<geometry_msgs::Pose> > calibration::samples_ [private] |
the positions saved from the cameras
Definition at line 102 of file calibration.hpp.