Go to the documentation of this file.
46 const std::string &global_frame,
47 const std::string &robot_frame,
49 : tf_listener_(tf_listener), global_frame_(global_frame), robot_frame_(robot_frame), tf_timeout_(tf_timeout)
61 ROS_ERROR_STREAM(
"Can not get the robot pose in the global frame. - robot frame: \""
#define ROS_ERROR_STREAM(args)
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
Computes the robot pose.
mbf_utility
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:44