Go to the documentation of this file.
38 #include <geometry_msgs/TransformStamped.h>
49 : stamp_(data.
header.stamp)
51 , child_frame_id_(child_frame_id)
53 const geometry_msgs::Quaternion& o = data.transform.rotation;
55 const geometry_msgs::Vector3& v = data.transform.translation;
60 : max_storage_time_(max_storage_time)
70 snprintf(str,
sizeof(str),
"Lookup would require extrapolation at time %.09f, but only time %.09f is in the buffer", t0.
toSec(), t1.
toSec());
85 "Lookup would require extrapolation %.09fs into the future. Requested time %.09f but the latest data is at time %.09f",
99 "Lookup would require extrapolation %.09fs into the past. Requested time %.09f but the earliest data is at time %.09f",
130 if (ts.
stamp_ == target_time)
145 if (target_time == latest_time)
150 else if (target_time == earliest_time)
156 else if (target_time > latest_time)
161 else if (target_time < earliest_time)
169 L_TransformStorage::iterator storage_it;
171 storage_target_time.
stamp_ = target_time;
173 storage_it = std::lower_bound(
176 storage_target_time, std::greater<TransformStorage>());
179 one = &*(storage_it);
180 two = &*(--storage_it);
213 int num_nodes =
findClosest(p_temp_1, p_temp_2, time, error_str);
218 else if (num_nodes == 1)
220 data_out = *p_temp_1;
222 else if (num_nodes == 2)
230 data_out = *p_temp_1;
246 int num_nodes =
findClosest(p_temp_1, p_temp_2, time, error_str);
257 L_TransformStorage::iterator storage_it =
storage_.begin();
265 *error_str =
"TF_OLD_DATA ignoring data from the past (Possible reasons are listed at http://wiki.ros.org/tf/Errors%%20explained)";
274 if (storage_it->stamp_ <= new_data.
stamp_)
278 if (storage_it !=
storage_.end() && storage_it->stamp_ == new_data.
stamp_)
282 *error_str =
"TF_REPEATED_DATA ignoring data with redundant timestamp";
288 storage_.insert(storage_it, new_data);
ros::Duration max_storage_time_
virtual ros::Time getOldestTimestamp()
Get the oldest timestamp cached.
virtual bool insertData(const TransformStorage &new_data, std::string *error_str=0)
Insert data into the cache.
virtual void clearList()
Clear the list of stored values.
virtual CompactFrameID getParent(ros::Time time, std::string *error_str)
Retrieve the parent at a specific time.
void interpolate(const TransformStorage &one, const TransformStorage &two, ros::Time time, TransformStorage &output)
virtual unsigned int getListLength()
Debugging information methods.
bool operator>(const TransformStorage &lhs, const TransformStorage &rhs)
uint8_t findClosest(TransformStorage *&one, TransformStorage *&two, ros::Time target_time, std::string *error_str)
A helper function for getData.
L_TransformStorage storage_
void createExtrapolationException1(ros::Time t0, ros::Time t1, std::string *error_str)
virtual bool getData(ros::Time time, TransformStorage &data_out, std::string *error_str=0)
Virtual methods.
std_msgs::Header const * header(const M &m)
std::pair< ros::Time, CompactFrameID > P_TimeAndFrameID
virtual ros::Time getLatestTimestamp()
Get the latest timestamp cached.
void createExtrapolationException3(ros::Time t0, ros::Time t1, std::string *error_str)
TimeCache(ros::Duration max_storage_time=ros::Duration().fromNSec(DEFAULT_MAX_STORAGE_TIME))
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
TF2SIMD_FORCE_INLINE Quaternion slerp(const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
Return the result of spherical linear interpolation betwen two quaternions.
double tf2Scalar
The tf2Scalar type abstracts floating point numbers, to easily switch between double and single float...
virtual P_TimeAndFrameID getLatestTimeAndParent()
Get the latest time stored in this cache, and the parent associated with it. Returns parent = 0 if no...
void createExtrapolationException2(ros::Time t0, ros::Time t1, std::string *error_str)
tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:11