#include <robot_state_display.h>

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::ColorProperty * | attached_body_color_property_ |
| rviz::BoolProperty * | enable_collision_visible_ |
| rviz::BoolProperty * | enable_link_highlight_ |
| rviz::BoolProperty * | enable_visual_visible_ |
| std::map< std::string, std_msgs::ColorRGBA > | highlights_ |
| robot_model::RobotModelConstPtr | kmodel_ |
| robot_state::RobotStatePtr | kstate_ |
| bool | load_robot_model_ |
| rdf_loader::RDFLoaderPtr | rdf_loader_ |
| RobotStateVisualizationPtr | robot_ |
| rviz::FloatProperty * | robot_alpha_property_ |
| rviz::StringProperty * | robot_description_property_ |
| ros::Subscriber | robot_state_subscriber_ |
| rviz::RosTopicProperty * | robot_state_topic_property_ |
| rviz::StringProperty * | root_link_name_property_ |
| ros::NodeHandle | root_nh_ |
| rviz::BoolProperty * | show_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 () |
Definition at line 68 of file robot_state_display.h.
Definition at line 62 of file robot_state_display.cpp.
Definition at line 105 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::calculateOffsetPosition | ( | ) | [protected] |
Set the scene node's position, given the target frame and the planning frame.
Definition at line 414 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedAllLinks | ( | ) | [private, slot] |
Definition at line 131 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedAttachedBodyColor | ( | ) | [private, slot] |
Definition at line 251 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedEnableCollisionVisible | ( | ) | [private, slot] |
Definition at line 186 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedEnableLinkHighlight | ( | ) | [private, slot] |
Definition at line 163 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedEnableVisualVisible | ( | ) | [private, slot] |
Definition at line 181 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedRobotDescription | ( | ) | [private, slot] |
Definition at line 266 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedRobotSceneAlpha | ( | ) | [private, slot] |
Definition at line 276 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedRobotStateTopic | ( | ) | [private, slot] |
Definition at line 292 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::changedRootLinkName | ( | ) | [private, slot] |
Definition at line 272 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::fixedFrameChanged | ( | ) | [protected, virtual] |
Reimplemented from rviz::Display.
Definition at line 428 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.
| void moveit_rviz_plugin::RobotStateDisplay::loadRobotModel | ( | ) | [protected] |
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 383 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::onEnable | ( | ) | [protected, virtual] |
Reimplemented from rviz::Display.
Definition at line 374 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::onInitialize | ( | ) | [protected, virtual] |
Reimplemented from rviz::Display.
Definition at line 109 of file robot_state_display.cpp.
| void moveit_rviz_plugin::RobotStateDisplay::reset | ( | void | ) | [virtual] |
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 391 of file robot_state_display.cpp.
rviz::ColorProperty* moveit_rviz_plugin::RobotStateDisplay::attached_body_color_property_ [protected] |
Definition at line 141 of file robot_state_display.h.
Definition at line 144 of file robot_state_display.h.
Definition at line 142 of file robot_state_display.h.
Definition at line 143 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.
bool moveit_rviz_plugin::RobotStateDisplay::load_robot_model_ [protected] |
Definition at line 135 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 140 of file robot_state_display.h.
rviz::StringProperty* moveit_rviz_plugin::RobotStateDisplay::robot_description_property_ [protected] |
Definition at line 137 of file robot_state_display.h.
Definition at line 127 of file robot_state_display.h.
rviz::RosTopicProperty* moveit_rviz_plugin::RobotStateDisplay::robot_state_topic_property_ [protected] |
Definition at line 139 of file robot_state_display.h.
Definition at line 138 of file robot_state_display.h.
Definition at line 126 of file robot_state_display.h.
Definition at line 145 of file robot_state_display.h.
bool moveit_rviz_plugin::RobotStateDisplay::update_state_ [protected] |
Definition at line 134 of file robot_state_display.h.