Go to the documentation of this file.
75 "tf_projection parameters \"base_link_frame\", \"projection_frame\", \"target_frame\", and \"frame\" "
76 "are replaced by \"source_frame\", \"projection_surface_frame\", \"parent_frame\", and \"projected_frame\"");
127 trans.
setData(rot_inv * trans);
131 const float yaw =
tf2::getYaw(trans.getRotation());
141 geometry_msgs::TransformStamped trans_out =
tf2::toMsg(result);
144 const double yaw =
tf2::getYaw(trans_out.transform.rotation);
170 int main(
int argc,
char* argv[])
tf2_ros::StaticTransformBroadcaster tf_static_broadcaster_
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void setData(const T &input)
double getYaw(const A &a)
void fromMsg(const A &, B &b)
#define ROS_WARN_THROTTLE(period,...)
tf2_ros::Buffer tf_buffer_
std::string projection_surface_frame_
tf2_ros::TransformListener tf_listener_
int main(int argc, char *argv[])
void cbTimer(const ros::TimerEvent &event)
std::string parent_frame_
std::string source_frame_
bool hasParam(const std::string &key) const
std::string projected_frame_
tf2::Transform projectTranslation(const tf2::Transform &trans, const tf2::Transform &trans_target)
Quaternion inverse() const
bool align_all_posture_to_source_
T param(const std::string ¶m_name, const T &default_val) const
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
tf2_ros::TransformBroadcaster tf_broadcaster_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
track_odometry
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:18