$search
#include <goal_tool.h>
Public Member Functions | |
virtual void | enumerateProperties (PropertyManager *property_manager, const CategoryPropertyWPtr &parent) |
const std::string & | getTopic () |
GoalTool (const std::string &name, char shortcut_key, VisualizationManager *manager) | |
virtual bool | hasProperties () |
void | setTopic (const std::string &topic) |
virtual | ~GoalTool () |
Protected Member Functions | |
virtual void | onPoseSet (double x, double y, double theta) |
Protected Attributes | |
ros::NodeHandle | nh_ |
ros::Publisher | pub_ |
std::string | topic_ |
StringPropertyWPtr | topic_property_ |
Definition at line 49 of file goal_tool.h.
rviz::GoalTool::GoalTool | ( | const std::string & | name, | |
char | shortcut_key, | |||
VisualizationManager * | manager | |||
) |
Definition at line 33 of file goal_tool.cpp.
rviz::GoalTool::~GoalTool | ( | ) | [virtual] |
Definition at line 39 of file goal_tool.cpp.
void rviz::GoalTool::enumerateProperties | ( | PropertyManager * | property_manager, | |
const CategoryPropertyWPtr & | parent | |||
) | [virtual] |
Reimplemented from rviz::Tool.
Definition at line 63 of file goal_tool.cpp.
const std::string& rviz::GoalTool::getTopic | ( | ) | [inline] |
Definition at line 55 of file goal_tool.h.
virtual bool rviz::GoalTool::hasProperties | ( | ) | [inline, virtual] |
Reimplemented from rviz::Tool.
Definition at line 57 of file goal_tool.h.
void rviz::GoalTool::onPoseSet | ( | double | x, | |
double | y, | |||
double | theta | |||
) | [protected, virtual] |
Implements rviz::PoseTool.
Definition at line 49 of file goal_tool.cpp.
void rviz::GoalTool::setTopic | ( | const std::string & | topic | ) |
Definition at line 43 of file goal_tool.cpp.
ros::NodeHandle rviz::GoalTool::nh_ [protected] |
Definition at line 65 of file goal_tool.h.
ros::Publisher rviz::GoalTool::pub_ [protected] |
Definition at line 66 of file goal_tool.h.
std::string rviz::GoalTool::topic_ [protected] |
Definition at line 63 of file goal_tool.h.
StringPropertyWPtr rviz::GoalTool::topic_property_ [protected] |
Definition at line 68 of file goal_tool.h.