Public Member Functions | Protected Member Functions | Protected Attributes | Private Slots
moveit_rviz_plugin::RobotStateDisplay Class Reference

#include <robot_state_display.h>

Inheritance diagram for moveit_rviz_plugin::RobotStateDisplay:
Inheritance graph
[legend]

List of all members.

Public Member Functions

const
robot_model::RobotModelConstPtr & 
getRobotModel () const
virtual void reset ()
 RobotStateDisplay ()
void setLinkColor (const std::string &link_name, const QColor &color)
void unsetLinkColor (const std::string &link_name)
virtual void update (float wall_dt, float ros_dt)
virtual ~RobotStateDisplay ()

Protected Member Functions

void calculateOffsetPosition ()
 Set the scene node's position, given the target frame and the planning frame.
virtual void fixedFrameChanged ()
void loadRobotModel ()
void newRobotStateCallback (const moveit_msgs::DisplayRobotState::ConstPtr &state)
virtual void onDisable ()
virtual void onEnable ()
virtual void onInitialize ()
void setHighlight (const std::string &link_name, const std_msgs::ColorRGBA &color)
void setLinkColor (rviz::Robot *robot, const std::string &link_name, const QColor &color)
void setRobotHighlights (const moveit_msgs::DisplayRobotState::_highlight_links_type &highlight_links)
void unsetHighlight (const std::string &link_name)
void unsetLinkColor (rviz::Robot *robot, const std::string &link_name)

Protected Attributes

rviz::ColorPropertyattached_body_color_property_
rviz::BoolPropertyenable_collision_visible_
rviz::BoolPropertyenable_link_highlight_
rviz::BoolPropertyenable_visual_visible_
std::map< std::string,
std_msgs::ColorRGBA > 
highlights_
robot_model::RobotModelConstPtr kmodel_
robot_state::RobotStatePtr kstate_
rdf_loader::RDFLoaderPtr rdf_loader_
RobotStateVisualizationPtr robot_
rviz::FloatPropertyrobot_alpha_property_
rviz::StringPropertyrobot_description_property_
ros::Subscriber robot_state_subscriber_
rviz::RosTopicPropertyrobot_state_topic_property_
rviz::StringPropertyroot_link_name_property_
ros::NodeHandle root_nh_
rviz::BoolPropertyshow_all_links_
bool update_state_

Private Slots

void changedAllLinks ()
void changedAttachedBodyColor ()
void changedEnableCollisionVisible ()
void changedEnableLinkHighlight ()
void changedEnableVisualVisible ()
void changedRobotDescription ()
void changedRobotSceneAlpha ()
void changedRobotStateTopic ()
void changedRootLinkName ()

Detailed Description

Definition at line 68 of file robot_state_display.h.


Constructor & Destructor Documentation

Definition at line 62 of file robot_state_display.cpp.

Definition at line 105 of file robot_state_display.cpp.


Member Function Documentation

Set the scene node's position, given the target frame and the planning frame.

Definition at line 413 of file robot_state_display.cpp.

Definition at line 131 of file robot_state_display.cpp.

Definition at line 251 of file robot_state_display.cpp.

Definition at line 186 of file robot_state_display.cpp.

Definition at line 163 of file robot_state_display.cpp.

Definition at line 181 of file robot_state_display.cpp.

Definition at line 266 of file robot_state_display.cpp.

Definition at line 276 of file robot_state_display.cpp.

Definition at line 292 of file robot_state_display.cpp.

Definition at line 272 of file robot_state_display.cpp.

Reimplemented from rviz::Display.

Definition at line 427 of file robot_state_display.cpp.

const robot_model::RobotModelConstPtr& moveit_rviz_plugin::RobotStateDisplay::getRobotModel ( ) const [inline]

Definition at line 79 of file robot_state_display.h.

Definition at line 348 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::newRobotStateCallback ( const moveit_msgs::DisplayRobotState::ConstPtr &  state) [protected]

Definition at line 305 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::onDisable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 390 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::onEnable ( ) [protected, virtual]

Reimplemented from rviz::Display.

Definition at line 373 of file robot_state_display.cpp.

Reimplemented from rviz::Display.

Definition at line 109 of file robot_state_display.cpp.

Reimplemented from rviz::Display.

Definition at line 118 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::setHighlight ( const std::string &  link_name,
const std_msgs::ColorRGBA &  color 
) [protected]

Definition at line 143 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::setLinkColor ( const std::string &  link_name,
const QColor &  color 
)

Definition at line 317 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::setLinkColor ( rviz::Robot robot,
const std::string &  link_name,
const QColor &  color 
) [protected]

Definition at line 327 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::setRobotHighlights ( const moveit_msgs::DisplayRobotState::_highlight_links_type &  highlight_links) [protected]

Definition at line 196 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::unsetHighlight ( const std::string &  link_name) [protected]

Definition at line 153 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::unsetLinkColor ( const std::string &  link_name)

Definition at line 322 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::unsetLinkColor ( rviz::Robot robot,
const std::string &  link_name 
) [protected]

Definition at line 336 of file robot_state_display.cpp.

void moveit_rviz_plugin::RobotStateDisplay::update ( float  wall_dt,
float  ros_dt 
) [virtual]

Reimplemented from rviz::Display.

Definition at line 398 of file robot_state_display.cpp.


Member Data Documentation

Definition at line 140 of file robot_state_display.h.

Definition at line 143 of file robot_state_display.h.

Definition at line 141 of file robot_state_display.h.

Definition at line 142 of file robot_state_display.h.

std::map<std::string, std_msgs::ColorRGBA> moveit_rviz_plugin::RobotStateDisplay::highlights_ [protected]

Definition at line 133 of file robot_state_display.h.

robot_model::RobotModelConstPtr moveit_rviz_plugin::RobotStateDisplay::kmodel_ [protected]

Definition at line 131 of file robot_state_display.h.

robot_state::RobotStatePtr moveit_rviz_plugin::RobotStateDisplay::kstate_ [protected]

Definition at line 132 of file robot_state_display.h.

rdf_loader::RDFLoaderPtr moveit_rviz_plugin::RobotStateDisplay::rdf_loader_ [protected]

Definition at line 130 of file robot_state_display.h.

RobotStateVisualizationPtr moveit_rviz_plugin::RobotStateDisplay::robot_ [protected]

Definition at line 129 of file robot_state_display.h.

Definition at line 139 of file robot_state_display.h.

Definition at line 136 of file robot_state_display.h.

Definition at line 127 of file robot_state_display.h.

Definition at line 138 of file robot_state_display.h.

Definition at line 137 of file robot_state_display.h.

Definition at line 126 of file robot_state_display.h.

Definition at line 144 of file robot_state_display.h.

Definition at line 134 of file robot_state_display.h.


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


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:22:14