moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Slots | Signals | Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes | List of all members
moveit_setup::RVizPanel Class Reference

#include <rviz_panel.hpp>

Inheritance diagram for moveit_setup::RVizPanel:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::RVizPanel:
Collaboration graph
[legend]

Public Slots

void highlightLink (const std::string &link_name, const QColor &color)
 
void highlightGroup (const std::string &group_name)
 
void unhighlightAll ()
 

Signals

void highlightLinkSignal (const std::string &link_name, const QColor &color)
 
void highlightGroupSignal (const std::string &group_name)
 
void unhighlightAllSignal ()
 

Public Member Functions

 RVizPanel (QWidget *parent, const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr &node_abstraction, const DataWarehousePtr &config_data)
 
 ~RVizPanel () override
 
bool isReadyForInitialization () const
 
void initialize ()
 
void updateFixedFrame ()
 
QWidget * getParentWindow () override
 
rviz_common::PanelDockWidget * addPane (const QString &, QWidget *, Qt::DockWidgetArea=Qt::LeftDockWidgetArea, bool=true) override
 
void setStatus (const QString &) override
 

Protected Slots

void highlightLinkEvent (const std::string &link_name, const QColor &color)
 
void highlightGroupEvent (const std::string &group_name)
 
void unhighlightAllEvent ()
 

Protected Member Functions

moveit::core::RobotModelPtr getRobotModel () const
 

Protected Attributes

QWidget * parent_
 
rviz_common::RenderPanel * rviz_render_panel_ { nullptr }
 
rviz_common::VisualizationManager * rviz_manager_ { nullptr }
 
moveit_rviz_plugin::RobotStateDisplayrobot_state_display_ { nullptr }
 
rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr node_abstraction_
 
rclcpp::Node::SharedPtr node_
 
std::shared_ptr< rclcpp::Logger > logger_
 
DataWarehousePtr config_data_
 

Detailed Description

Definition at line 57 of file rviz_panel.hpp.

Constructor & Destructor Documentation

◆ RVizPanel()

moveit_setup::RVizPanel::RVizPanel ( QWidget *  parent,
const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr &  node_abstraction,
const DataWarehousePtr &  config_data 
)

Definition at line 45 of file rviz_panel.cpp.

Here is the call graph for this function:

◆ ~RVizPanel()

moveit_setup::RVizPanel::~RVizPanel ( )
override

Definition at line 120 of file rviz_panel.cpp.

Member Function Documentation

◆ addPane()

rviz_common::PanelDockWidget* moveit_setup::RVizPanel::addPane ( const QString &  ,
QWidget *  ,
Qt::DockWidgetArea  = Qt::LeftDockWidgetArea,
bool  = true 
)
inlineoverride

Definition at line 77 of file rviz_panel.hpp.

◆ getParentWindow()

QWidget* moveit_setup::RVizPanel::getParentWindow ( )
inlineoverride

Definition at line 72 of file rviz_panel.hpp.

◆ getRobotModel()

moveit::core::RobotModelPtr moveit_setup::RVizPanel::getRobotModel ( ) const
protected

Definition at line 130 of file rviz_panel.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ highlightGroup

void moveit_setup::RVizPanel::highlightGroup ( const std::string &  group_name)
inlineslot

Highlight a robot group

Definition at line 104 of file rviz_panel.hpp.

◆ highlightGroupEvent

void moveit_setup::RVizPanel::highlightGroupEvent ( const std::string &  group_name)
protectedslot

Definition at line 172 of file rviz_panel.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ highlightGroupSignal

void moveit_setup::RVizPanel::highlightGroupSignal ( const std::string &  group_name)
signal
Here is the caller graph for this function:

◆ highlightLink

void moveit_setup::RVizPanel::highlightLink ( const std::string &  link_name,
const QColor &  color 
)
inlineslot

Highlight a link of the robot

Parameters
link_namename of link to highlight

Definition at line 96 of file rviz_panel.hpp.

Here is the caller graph for this function:

◆ highlightLinkEvent

void moveit_setup::RVizPanel::highlightLinkEvent ( const std::string &  link_name,
const QColor &  color 
)
protectedslot

Definition at line 159 of file rviz_panel.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ highlightLinkSignal

void moveit_setup::RVizPanel::highlightLinkSignal ( const std::string &  link_name,
const QColor &  color 
)
signal
Here is the caller graph for this function:

◆ initialize()

void moveit_setup::RVizPanel::initialize ( )

Definition at line 62 of file rviz_panel.cpp.

Here is the call graph for this function:

◆ isReadyForInitialization()

bool moveit_setup::RVizPanel::isReadyForInitialization ( ) const
inline

Definition at line 65 of file rviz_panel.hpp.

Here is the call graph for this function:

◆ setStatus()

void moveit_setup::RVizPanel::setStatus ( const QString &  )
inlineoverride

Definition at line 85 of file rviz_panel.hpp.

◆ unhighlightAll

void moveit_setup::RVizPanel::unhighlightAll ( )
inlineslot

Unhighlight all links of a robot

Definition at line 112 of file rviz_panel.hpp.

Here is the caller graph for this function:

◆ unhighlightAllEvent

void moveit_setup::RVizPanel::unhighlightAllEvent ( )
protectedslot

Definition at line 195 of file rviz_panel.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ unhighlightAllSignal

void moveit_setup::RVizPanel::unhighlightAllSignal ( )
signal
Here is the caller graph for this function:

◆ updateFixedFrame()

void moveit_setup::RVizPanel::updateFixedFrame ( )

Definition at line 144 of file rviz_panel.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ config_data_

DataWarehousePtr moveit_setup::RVizPanel::config_data_
protected

Definition at line 139 of file rviz_panel.hpp.

◆ logger_

std::shared_ptr<rclcpp::Logger> moveit_setup::RVizPanel::logger_
protected

Definition at line 137 of file rviz_panel.hpp.

◆ node_

rclcpp::Node::SharedPtr moveit_setup::RVizPanel::node_
protected

Definition at line 136 of file rviz_panel.hpp.

◆ node_abstraction_

rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr moveit_setup::RVizPanel::node_abstraction_
protected

Definition at line 135 of file rviz_panel.hpp.

◆ parent_

QWidget* moveit_setup::RVizPanel::parent_
protected

Definition at line 131 of file rviz_panel.hpp.

◆ robot_state_display_

moveit_rviz_plugin::RobotStateDisplay* moveit_setup::RVizPanel::robot_state_display_ { nullptr }
protected

Definition at line 134 of file rviz_panel.hpp.

◆ rviz_manager_

rviz_common::VisualizationManager* moveit_setup::RVizPanel::rviz_manager_ { nullptr }
protected

Definition at line 133 of file rviz_panel.hpp.

◆ rviz_render_panel_

rviz_common::RenderPanel* moveit_setup::RVizPanel::rviz_render_panel_ { nullptr }
protected

Definition at line 132 of file rviz_panel.hpp.


The documentation for this class was generated from the following files: