64 , tf_listener_(tf_buffer_)
66 if (pnh_.
hasParam(
"base_link_frame") ||
72 "tf_projection parameters \"base_link_frame\", \"projection_frame\", \"target_frame\", and \"frame\" " 73 "are replaced by \"source_frame\", \"projection_surface_frame\", \"parent_frame\", and \"projected_frame\"");
75 pnh_.
param(
"base_link_frame", source_frame_, std::string(
"base_link"));
76 pnh_.
param(
"projection_frame", projection_surface_frame_, std::string(
"map"));
77 pnh_.
param(
"target_frame", parent_frame_, std::string(
"map"));
78 pnh_.
param(
"frame", projected_frame_, std::string(
"base_link_projected"));
82 pnh_.
param(
"source_frame", source_frame_, std::string(
"base_link"));
83 pnh_.
param(
"projection_surface_frame", projection_surface_frame_, std::string(
"map"));
84 pnh_.
param(
"parent_frame", parent_frame_, std::string(
"map"));
85 pnh_.
param(
"projected_frame", projected_frame_, std::string(
"base_link_projected"));
88 pnh_.
param(
"hz", rate_, 10.0);
89 pnh_.
param(
"tf_tolerance", tf_tolerance_, 0.1);
90 pnh_.
param(
"flat", flat_,
false);
91 pnh_.
param(
"project_posture", project_posture_,
false);
112 if (project_posture_)
114 const float yaw =
tf2::getYaw(trans.getRotation());
123 geometry_msgs::TransformStamped trans_out =
tf2::toMsg(result);
126 const float yaw =
tf2::getYaw(trans_out.transform.rotation);
145 int main(
int argc,
char* argv[])
void cbTimer(const ros::TimerEvent &event)
std::string parent_frame_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_WARN_ONCE(...)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void fromMsg(const A &, B &b)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
tf2_ros::TransformBroadcaster tf_broadcaster_
double getYaw(const A &a)
std::string source_frame_
tf2::Transform projectTranslation(const tf2::Transform &trans, const tf2::Transform &trans_target)
tf2_ros::Buffer tf_buffer_
std::string projection_surface_frame_
bool hasParam(const std::string &key) const
tf2_ros::TransformListener tf_listener_
int main(int argc, char *argv[])
std::string projected_frame_