00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037 #include <ros/ros.h>
00038 #include <monocam_settler/monocam_settler.h>
00039
00040 using namespace monocam_settler;
00041
00042 monocam_settler::ConfigGoal getParamConfig(ros::NodeHandle& n)
00043 {
00044 monocam_settler::ConfigGoal config;
00045
00046 n.param("~tolerance", config.tolerance, 1.0);
00047 ROS_INFO("tolerance: %.3f", config.tolerance);
00048
00049 bool ignore_failures;
00050 n.param("~ignore_failures", ignore_failures, true);
00051 config.ignore_failures = ignore_failures;
00052 if (config.ignore_failures)
00053 ROS_INFO("Ignore Failures: True");
00054 else
00055 ROS_INFO("Ignore Failures: False");
00056
00057 double max_step;
00058 n.param("~max_step", max_step, 1000.0);
00059 config.max_step = ros::Duration(max_step);
00060 ROS_INFO("max step: [%.3fs]", config.max_step.toSec());
00061
00062 int cache_size;
00063 n.param("~cache_size", cache_size, 1000);
00064 if (cache_size < 0)
00065 ROS_FATAL("cache_size < 0. (cache_size==%i)", cache_size);
00066 config.cache_size = (unsigned int) cache_size;
00067 ROS_INFO("cache_size: [%u]", config.cache_size);
00068
00069 return config;
00070 }
00071
00072 void msgCallback(ros::Publisher* pub, MonocamSettler* settler, const calibration_msgs::CalibrationPatternConstPtr& msg)
00073 {
00074 bool success;
00075
00076 calibration_msgs::Interval interval;
00077 success = settler->add(msg, interval);
00078
00079 if (success)
00080 pub->publish(interval);
00081 else
00082 {
00083 interval.start = msg->header.stamp;
00084 interval.end = msg->header.stamp;
00085 pub->publish(interval);
00086 }
00087 }
00088
00089 int main(int argc, char** argv)
00090 {
00091 ros::init(argc, argv, "monocam_settler");
00092
00093 ros::NodeHandle n;
00094
00095
00096 monocam_settler::ConfigGoal config = getParamConfig(n);
00097 MonocamSettler settler;
00098 settler.configure(config);
00099
00100
00101 ros::Publisher pub = n.advertise<calibration_msgs::Interval>("settled", 1);
00102
00103
00104 boost::function<void (const calibration_msgs::CalibrationPatternConstPtr&)> cb = boost::bind(&msgCallback, &pub, &settler, _1);
00105 ros::Subscriber sub = n.subscribe(std::string("features"), 1, cb);
00106
00107 ros::spin();
00108 }