#include <tf_visual_tools.h>
|
void | publishAllTransforms (const ros::TimerEvent &e) |
| At a certain frequency update the tf transforms that we are tracking This is called internally by a clock, you should not need to use this TODO: make private in next release? More...
|
|
bool | publishTransform (const Eigen::Affine3d &transform, const std::string &from_frame, const std::string &to_frame) |
| Visualize transforms in Rviz, etc. More...
|
|
| TFVisualTools (double loop_hz=2) |
| Constructor. More...
|
|
Definition at line 64 of file tf_visual_tools.h.
rviz_visual_tools::TFVisualTools::TFVisualTools |
( |
double |
loop_hz = 2 | ) |
|
|
explicit |
Constructor.
- Parameters
-
loop_hz | - how often tf is published |
Definition at line 49 of file tf_visual_tools.cpp.
void rviz_visual_tools::TFVisualTools::publishAllTransforms |
( |
const ros::TimerEvent & |
e | ) |
|
At a certain frequency update the tf transforms that we are tracking This is called internally by a clock, you should not need to use this TODO: make private in next release?
Definition at line 99 of file tf_visual_tools.cpp.
bool rviz_visual_tools::TFVisualTools::publishTransform |
( |
const Eigen::Affine3d & |
transform, |
|
|
const std::string & |
from_frame, |
|
|
const std::string & |
to_frame |
|
) |
| |
Visualize transforms in Rviz, etc.
- Returns
- true on success
Definition at line 57 of file tf_visual_tools.cpp.
ros::Timer rviz_visual_tools::TFVisualTools::non_realtime_loop_ |
|
private |
std::vector<geometry_msgs::TransformStamped> rviz_visual_tools::TFVisualTools::transforms_ |
|
private |
The documentation for this class was generated from the following files: