35 #ifndef LASER_JOINT_PROCESSOR_LASER_JOINT_PROCESSOR_H_ 36 #define LASER_JOINT_PROCESSOR_LASER_JOINT_PROCESSOR_H_ 42 #include <sensor_msgs/JointState.h> 43 #include <calibration_msgs/DenseLaserSnapshot.h> 44 #include <calibration_msgs/CalibrationPattern.h> 45 #include <calibration_msgs/JointStateCalibrationPattern.h> 58 void setJointNames(
const std::vector<std::string>& joint_names);
60 bool addJointState(
const sensor_msgs::JointStateConstPtr& joint_state);
62 bool isSnapshotEarly(
const calibration_msgs::DenseLaserSnapshot& snapshot)
const;
63 bool isSnapshotLate(
const calibration_msgs::DenseLaserSnapshot& snapshot)
const;
69 const calibration_msgs::CalibrationPattern& features,
70 calibration_msgs::JointStateCalibrationPattern& result,
bool addJointState(const sensor_msgs::JointStateConstPtr &joint_state)
std::vector< std::string > joint_names_
ros::Time getLatestJointStateTime() const
JointImageInterpolator interp_
void setCacheSize(unsigned int max_size)
ros::Time getEarliestJointStateTime() const
settlerlib::SortedDeque< joint_states_settler::DeflatedJointStates > joint_state_cache_
bool processLaserData(const calibration_msgs::DenseLaserSnapshot &snapshot, const calibration_msgs::CalibrationPattern &features, calibration_msgs::JointStateCalibrationPattern &result, const ros::Duration &max_interp=ros::Duration(.25))
bool isSnapshotLate(const calibration_msgs::DenseLaserSnapshot &snapshot) const
joint_states_settler::JointStatesDeflater deflater_
bool isSnapshotEarly(const calibration_msgs::DenseLaserSnapshot &snapshot) const
void setJointNames(const std::vector< std::string > &joint_names)