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
00035 #ifndef LASER_JOINT_PROCESSOR_LASER_JOINT_PROCESSOR_H_
00036 #define LASER_JOINT_PROCESSOR_LASER_JOINT_PROCESSOR_H_
00037
00038 #include <laser_joint_processor/joint_imager.h>
00039 #include <laser_joint_processor/joint_image_interpolator.h>
00040 #include <settlerlib/sorted_deque.h>
00041 #include <joint_states_settler/joint_states_deflater.h>
00042 #include <sensor_msgs/JointState.h>
00043 #include <calibration_msgs/DenseLaserSnapshot.h>
00044 #include <calibration_msgs/CalibrationPattern.h>
00045 #include <calibration_msgs/JointStateCalibrationPattern.h>
00046
00047
00048 namespace laser_joint_processor
00049 {
00050
00051 class LaserJointProcessor
00052 {
00053 public:
00054
00055 LaserJointProcessor();
00056
00057 void setCacheSize(unsigned int max_size);
00058 void setJointNames(const std::vector<std::string>& joint_names);
00059
00060 bool addJointState(const sensor_msgs::JointStateConstPtr& joint_state);
00061
00062 bool isSnapshotEarly(const calibration_msgs::DenseLaserSnapshot& snapshot) const;
00063 bool isSnapshotLate( const calibration_msgs::DenseLaserSnapshot& snapshot) const;
00064
00065 ros::Time getEarliestJointStateTime() const;
00066 ros::Time getLatestJointStateTime() const;
00067
00068 bool processLaserData( const calibration_msgs::DenseLaserSnapshot& snapshot,
00069 const calibration_msgs::CalibrationPattern& features,
00070 calibration_msgs::JointStateCalibrationPattern& result,
00071 const ros::Duration& max_interp = ros::Duration(.25));
00072
00073 private:
00074 settlerlib::SortedDeque<joint_states_settler::DeflatedJointStates> joint_state_cache_;
00075 joint_states_settler::JointStatesDeflater deflater_;
00076 JointImager imager_;
00077 JointImageInterpolator interp_;
00078 std::vector<std::string> joint_names_;
00079 };
00080
00081 }
00082
00083 #endif
00084