50 Transformer(true, max_cache_time), node_(nh), tf2_listener_(*
Transformer::tf2_buffer_ptr_, nh, spin_thread)
66 const geometry_msgs::QuaternionStamped& msg_in,
67 geometry_msgs::QuaternionStamped& msg_out)
const
78 const geometry_msgs::Vector3Stamped& msg_in,
79 geometry_msgs::Vector3Stamped& msg_out)
const
88 const geometry_msgs::PointStamped& msg_in,
89 geometry_msgs::PointStamped& msg_out)
const
98 const geometry_msgs::PoseStamped& msg_in,
99 geometry_msgs::PoseStamped& msg_out)
const
142 const geometry_msgs::QuaternionStamped& msg_in,
143 const std::string& fixed_frame, geometry_msgs::QuaternionStamped& msg_out)
const
153 const geometry_msgs::Vector3Stamped& msg_in,
154 const std::string& fixed_frame, geometry_msgs::Vector3Stamped& msg_out)
const
163 const geometry_msgs::PointStamped& msg_in,
164 const std::string& fixed_frame, geometry_msgs::PointStamped& msg_out)
const
168 transformPoint(target_frame, target_time, pin, fixed_frame, pout);
173 const geometry_msgs::PoseStamped& msg_in,
174 const std::string& fixed_frame, geometry_msgs::PoseStamped& msg_out)
const
180 transformPose(target_frame, target_time, pin, fixed_frame, pout);
187 lookupTransform(target_frame, cloudIn.header.frame_id, cloudIn.header.stamp, transform);
192 const sensor_msgs::PointCloud& cloudIn,
193 const std::string& fixed_frame, sensor_msgs::PointCloud& cloudOut)
const
197 cloudIn.header.frame_id, cloudIn.header.stamp,
209 double x = basis[0].x() * in.x + basis[0].y() * in.y + basis[0].z() * in.z + origin.x();
210 double y = basis[1].x() * in.x + basis[1].y() * in.y + basis[1].z() * in.z + origin.y();
211 double z = basis[2].x() * in.x + basis[2].y() * in.y + basis[2].z() * in.z + origin.z();
213 out.x = x; out.y = y; out.z = z;
218 const ros::Time& target_time,
const sensor_msgs::PointCloud & cloudIn,
219 sensor_msgs::PointCloud & cloudOut)
const
221 tf::Vector3 origin = net_transform.
getOrigin();
224 unsigned int length = cloudIn.points.size();
227 if (&cloudIn != &cloudOut)
229 cloudOut.header = cloudIn.header;
230 cloudOut.points.resize(
length);
231 cloudOut.channels.resize(cloudIn.channels.size());
232 for (
unsigned int i = 0 ; i < cloudIn.channels.size() ; ++i)
233 cloudOut.channels[i] = cloudIn.channels[i];
237 cloudOut.header.stamp = target_time;
238 cloudOut.header.frame_id = target_frame;
239 for (
unsigned int i = 0; i <
length ; i++) {