#include <frames.hpp>
Signals | |
void | displayErrorMessageBox (const QString, const QString, const QString) |
Signals inherited from rviz::Panel | |
void | configChanged () |
Public Member Functions | |
Frames (QWidget *parent=NULL) | |
virtual | ~Frames () |
Public Member Functions inherited from rviz::Panel | |
virtual QString | getClassId () const |
virtual QString | getDescription () const |
virtual QString | getName () const |
void | initialize (VisualizationManager *manager) |
virtual void | load (const Config &config) |
virtual void | onInitialize () |
Panel (QWidget *parent=0) | |
virtual void | save (Config config) const |
virtual void | setClassId (const QString &class_id) |
virtual void | setDescription (const QString &description) |
virtual void | setName (const QString &name) |
virtual | ~Panel () |
Protected Slots | |
void | displayErrorBoxHandler (const QString title, const QString message, const QString info_msg) |
void | load (const rviz::Config &config) |
void | save (rviz::Config config) const |
void | sendInformationButtonHandler () |
void | sendLoadedInformation () |
void | sendStartPoseInformation () |
void | sendToolInformation () |
void | sendTrajectoryFrameInformation () |
Protected Attributes | |
ros::NodeHandle | nh_ |
Pose * | start_pose_ |
geometry_msgs::Pose | start_pose_pose_ |
ros::Publisher | start_pose_pub_ |
Pose * | tool_ |
geometry_msgs::Pose | tool_pose_ |
ros::Publisher | tool_pub_ |
Pose * | trajectory_frame_ |
geometry_msgs::Pose | trajectory_frame_pose_ |
ros::Publisher | trajectory_frame_pub_ |
Protected Attributes inherited from rviz::Panel | |
VisualizationManager * | vis_manager_ |
Private Member Functions | |
void | updateInternalParameters () |
Definition at line 22 of file frames.hpp.
ram_qt_guis::Frames::Frames | ( | QWidget * | parent = NULL | ) |
Definition at line 5 of file frames.cpp.
|
virtual |
Definition at line 65 of file frames.cpp.
|
protectedslot |
Definition at line 166 of file frames.cpp.
|
signal |
|
protectedslot |
Definition at line 115 of file frames.cpp.
|
protectedslot |
Definition at line 158 of file frames.cpp.
|
protectedslot |
|
protectedslot |
Definition at line 124 of file frames.cpp.
|
protectedslot |
Definition at line 89 of file frames.cpp.
|
protectedslot |
Definition at line 102 of file frames.cpp.
|
protectedslot |
Definition at line 76 of file frames.cpp.
|
private |
Definition at line 69 of file frames.cpp.
|
protected |
Definition at line 56 of file frames.hpp.
|
protected |
Definition at line 53 of file frames.hpp.
|
protected |
Definition at line 61 of file frames.hpp.
|
protected |
Definition at line 60 of file frames.hpp.
|
protected |
Definition at line 54 of file frames.hpp.
|
protected |
Definition at line 63 of file frames.hpp.
|
protected |
Definition at line 62 of file frames.hpp.
|
protected |
Definition at line 52 of file frames.hpp.
|
protected |
Definition at line 59 of file frames.hpp.
|
protected |
Definition at line 58 of file frames.hpp.