59 return cache->
getParent(time, error_string);
76 : source_to_top_quat(0.0, 0.0, 0.0, 1.0)
77 , source_to_top_vec(0.0, 0.0, 0.0)
78 , target_to_top_quat(0.0, 0.0, 0.0, 1.0)
79 , target_to_top_vec(0.0, 0.0, 0.0)
80 , result_quat(0.0, 0.0, 0.0, 1.0)
81 , result_vec(0.0, 0.0, 0.0)
87 if (!cache->
getData(time, st, error_string))
99 source_to_top_vec =
quatRotate(st.rotation_, source_to_top_vec) + st.translation_;
100 source_to_top_quat = st.rotation_ * source_to_top_quat;
104 target_to_top_vec =
quatRotate(st.rotation_, target_to_top_vec) + st.translation_;
105 target_to_top_quat = st.rotation_ * target_to_top_quat;
116 result_vec = source_to_top_vec;
117 result_quat = source_to_top_quat;
122 tf::Vector3 inv_target_vec =
quatRotate(inv_target_quat, -target_to_top_vec);
123 result_vec = inv_target_vec;
124 result_quat = inv_target_quat;
130 tf::Vector3 inv_target_vec =
quatRotate(inv_target_quat, -target_to_top_vec);
132 result_vec =
quatRotate(inv_target_quat, source_to_top_vec) + inv_target_vec;
133 result_quat = inv_target_quat * source_to_top_quat;
155 ROS_DEBUG(
"tf::assert_resolved just calls tf::resolve");
159 std::string
tf::resolve(
const std::string& prefix,
const std::string& frame_name)
162 if (frame_name.size() > 0)
163 if (frame_name[0] ==
'/')
167 if (prefix.size() > 0)
169 if (prefix[0] ==
'/')
172 composite.append(
"/");
173 composite.append(frame_name);
178 std::string composite;
179 composite.append(prefix);
180 composite.append(
"/");
181 composite.append(frame_name);
188 std::string composite;
189 composite.append(frame_name);
197 if (frame_name.size() > 0)
198 if (frame_name[0] ==
'/')
200 std::string shorter = frame_name;
211 fall_back_to_wall_time_(false),
212 tf2_buffer_ptr_(
std::make_shared<
tf2_ros::Buffer>(cache_time))
231 geometry_msgs::TransformStamped msgtf;
241 geometry_msgs::TransformStamped output =
252 geometry_msgs::TransformStamped output =
262 geometry_msgs::Twist& twist)
const
265 lookupTwist(tracking_frame, observation_frame, observation_frame,
tf::Point(0,0,0), tracking_frame, time, averaging_interval, twist);
270 void Transformer::lookupTwist(
const std::string& tracking_frame,
const std::string& observation_frame,
const std::string& reference_frame,
271 const tf::Point & reference_point,
const std::string& reference_point_frame,
273 geometry_msgs::Twist& twist)
const
280 target_time = latest_time;
284 ros::Time end_time = std::min(target_time + averaging_interval *0.5 , latest_time);
286 ros::Time start_time = std::max(
ros::Time().fromSec(.00001) + averaging_interval, end_time) - averaging_interval;
287 ros::Duration corrected_averaging_interval = end_time - start_time;
299 double delta_x = end.
getOrigin().getX() -
start.getOrigin().getX();
300 double delta_y = end.
getOrigin().getY() -
start.getOrigin().getY();
301 double delta_z = end.
getOrigin().getZ() -
start.getOrigin().getZ();
304 tf::Vector3 twist_vel ((delta_x)/corrected_averaging_interval.
toSec(),
305 (delta_y)/corrected_averaging_interval.
toSec(),
306 (delta_z)/corrected_averaging_interval.
toSec());
307 tf::Vector3 twist_rot = o * (ang / corrected_averaging_interval.
toSec());
316 tf::Vector3 out_rot =
inverse.getBasis() * twist_rot;
317 tf::Vector3 out_vel =
inverse.getBasis()* twist_vel +
inverse.getOrigin().cross(out_rot);
330 out_vel = out_vel + out_rot * delta;
339 twist.linear.x = out_vel.x();
340 twist.linear.y = out_vel.y();
341 twist.linear.z = out_vel.z();
342 twist.angular.x = out_rot.x();
343 twist.angular.y = out_rot.y();
344 twist.angular.z = out_rot.z();
351 std::string* error_msg)
const
359 const ros::Time& time, std::string* error_msg)
const
367 const ros::Time& source_time,
const std::string& fixed_frame,
368 std::string* error_msg)
const
376 const ros::Time& source_time,
const std::string& fixed_frame,
378 std::string* error_msg)
const
399 ROS_WARN(
"Transformer::setExtrapolationLimit is deprecated and does not do anything");
411 return rhs.second == id;
422 return tf2_buffer_ptr_->_getLatestCommonTime(source_id, target_id, time, error_string);
430 source_frame, source_time,
431 fixed_frame, output);
460 stamped_out.
setData( transform * stamped_in);
474 tf::Vector3 end = stamped_in;
475 tf::Vector3 origin = tf::Vector3(0,0,0);
476 tf::Vector3 output = (transform * end) - (transform * origin);
489 stamped_out.
setData(transform * stamped_in);
499 stamped_out.
setData(transform * stamped_in);
507 const std::string& fixed_frame,
514 fixed_frame, transform);
516 stamped_out.
setData( transform * stamped_in);
524 const std::string& fixed_frame,
530 fixed_frame, transform);
533 tf::Vector3 end = stamped_in;
534 tf::Vector3 origin = tf::Vector3(0,0,0);
535 tf::Vector3 output = (transform * end) - (transform * origin);
545 const std::string& fixed_frame,
551 fixed_frame, transform);
553 stamped_out.
setData(transform * stamped_in);
560 const std::string& fixed_frame,
566 fixed_frame, transform);
568 stamped_out.
setData(transform * stamped_in);