$search
#include <planning_display.h>

Public Member Functions | |
| virtual void | createProperties () |
| virtual void | fixedFrameChanged () |
| float | getAlpha () |
| bool | getLoopDisplay () |
| const std::string & | getRobotDescription () |
| float | getStateDisplayTime () |
| const std::string & | getTopic () |
| void | initialize (const std::string &description_param, const std::string &kinematic_path_topic) |
| Initializes the display. | |
| bool | isCollisionVisible () |
| bool | isVisualVisible () |
| PlanningDisplay (const std::string &name, rviz::VisualizationManager *manager) | |
| void | setAlpha (float alpha) |
| void | setCollisionVisible (bool visible) |
| Set whether the collision representation should be displayed. | |
| void | setLoopDisplay (bool loop_display) |
| void | setRobotDescription (const std::string &description_param) |
| Set the robot description parameter. | |
| void | setStateDisplayTime (float time) |
| Set the amount of time each state should display for. | |
| void | setTopic (const std::string &topic) |
| Set the topic to listen on for the JointPath message. | |
| void | setVisualVisible (bool visible) |
| Set whether the visual mesh representation should be displayed. | |
| virtual void | targetFrameChanged () |
| virtual void | update (float wall_dt, float ros_dt) |
| virtual | ~PlanningDisplay () |
Protected Member Functions | |
| void | advertise () |
| Advertises any ROS topics. | |
| void | calculateRobotPosition () |
| Uses libTF to set the robot's position, given the target frame and the planning frame. | |
| void | incomingJointPath (const arm_navigation_msgs::DisplayTrajectory::ConstPtr &msg) |
| ROS callback for an incoming kinematic path message. | |
| void | load () |
| Loads a URDF from our description_param_. | |
| virtual void | onDisable () |
| virtual void | onEnable () |
| void | subscribe () |
| Subscribes to any ROS topics we need to subscribe to. | |
| void | unadvertise () |
| Unadvertises all ROS topics that we have advertised. | |
| void | unsubscribe () |
| Unsubscribes from all ROS topics we're currently subscribed to. | |
Protected Attributes | |
| float | alpha_ |
| rviz::FloatPropertyWPtr | alpha_property_ |
| bool | animating_path_ |
| rviz::BoolPropertyWPtr | collision_enabled_property_ |
| int | current_state_ |
| float | current_state_time_ |
| std::string | description_param_ |
| ROS parameter that contains the robot xml description. | |
| arm_navigation_msgs::DisplayTrajectory::ConstPtr | displaying_kinematic_path_message_ |
| planning_environment::RobotModels * | env_models_ |
| arm_navigation_msgs::DisplayTrajectory::ConstPtr | incoming_kinematic_path_message_ |
| const planning_models::KinematicModel * | kinematic_model_ |
| std::string | kinematic_path_topic_ |
| bool | loop_display_ |
| rviz::BoolPropertyWPtr | loop_display_property_ |
| bool | new_kinematic_path_ |
| rviz::Robot * | robot_ |
| Handles actually drawing the robot. | |
| rviz::StringPropertyWPtr | robot_description_property_ |
| float | state_display_time_ |
| rviz::FloatPropertyWPtr | state_display_time_property_ |
| ros::Publisher | state_publisher_ |
| ros::Subscriber | sub_ |
| rviz::ROSTopicStringPropertyWPtr | topic_property_ |
| rviz::BoolPropertyWPtr | visual_enabled_property_ |
Definition at line 71 of file planning_display.h.
| motion_planning_rviz_plugin::PlanningDisplay::PlanningDisplay | ( | const std::string & | name, | |
| rviz::VisualizationManager * | manager | |||
| ) |
Definition at line 91 of file planning_display.cpp.
| motion_planning_rviz_plugin::PlanningDisplay::~PlanningDisplay | ( | ) | [virtual] |
Definition at line 103 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::advertise | ( | ) | [protected] |
Advertises any ROS topics.
Definition at line 260 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::calculateRobotPosition | ( | ) | [protected] |
Uses libTF to set the robot's position, given the target frame and the planning frame.
Definition at line 390 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::createProperties | ( | ) | [virtual] |
Reimplemented from rviz::Display.
Definition at line 435 of file planning_display.cpp.
| virtual void motion_planning_rviz_plugin::PlanningDisplay::fixedFrameChanged | ( | ) | [inline, virtual] |
Implements rviz::Display.
Definition at line 131 of file planning_display.h.
| float motion_planning_rviz_plugin::PlanningDisplay::getAlpha | ( | ) | [inline] |
Definition at line 118 of file planning_display.h.
| bool motion_planning_rviz_plugin::PlanningDisplay::getLoopDisplay | ( | ) | [inline] |
Definition at line 121 of file planning_display.h.
| const std::string& motion_planning_rviz_plugin::PlanningDisplay::getRobotDescription | ( | ) | [inline] |
Definition at line 114 of file planning_display.h.
| float motion_planning_rviz_plugin::PlanningDisplay::getStateDisplayTime | ( | ) | [inline] |
Definition at line 116 of file planning_display.h.
| const std::string& motion_planning_rviz_plugin::PlanningDisplay::getTopic | ( | ) | [inline] |
Definition at line 115 of file planning_display.h.
| void motion_planning_rviz_plugin::PlanningDisplay::incomingJointPath | ( | const arm_navigation_msgs::DisplayTrajectory::ConstPtr & | msg | ) | [protected] |
ROS callback for an incoming kinematic path message.
Definition at line 424 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::initialize | ( | const std::string & | description_param, | |
| const std::string & | kinematic_path_topic | |||
| ) |
Initializes the display.
| description_param | The ROS parameter name which contains the robot xml description | |
| kinematic_path_topic | The topic to listen on for a NamedJointPath |
Definition at line 111 of file planning_display.cpp.
| bool motion_planning_rviz_plugin::PlanningDisplay::isCollisionVisible | ( | ) |
Definition at line 188 of file planning_display.cpp.
| bool motion_planning_rviz_plugin::PlanningDisplay::isVisualVisible | ( | ) |
Definition at line 183 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::load | ( | ) | [protected] |
Loads a URDF from our description_param_.
Definition at line 193 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::onDisable | ( | ) | [protected, virtual] |
Implements rviz::Display.
Definition at line 234 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::onEnable | ( | ) | [protected, virtual] |
Implements rviz::Display.
Definition at line 226 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setAlpha | ( | float | alpha | ) |
Definition at line 136 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setCollisionVisible | ( | bool | visible | ) |
Set whether the collision representation should be displayed.
| visible |
Definition at line 174 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setLoopDisplay | ( | bool | loop_display | ) |
Definition at line 130 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setRobotDescription | ( | const std::string & | description_param | ) |
Set the robot description parameter.
| description_param | The ROS parameter name which contains the robot xml description |
Definition at line 117 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setStateDisplayTime | ( | float | time | ) |
Set the amount of time each state should display for.
| time | The length of time, in seconds |
Definition at line 156 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setTopic | ( | const std::string & | topic | ) |
Set the topic to listen on for the JointPath message.
| topic | The ROS topic |
Definition at line 145 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::setVisualVisible | ( | bool | visible | ) |
Set whether the visual mesh representation should be displayed.
| visible |
Definition at line 165 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::subscribe | ( | ) | [protected] |
Subscribes to any ROS topics we need to subscribe to.
Definition at line 241 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::targetFrameChanged | ( | ) | [virtual] |
Implements rviz::Display.
Definition at line 430 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::unadvertise | ( | ) | [protected] |
Unadvertises all ROS topics that we have advertised.
Definition at line 269 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::unsubscribe | ( | ) | [protected] |
Unsubscribes from all ROS topics we're currently subscribed to.
Definition at line 255 of file planning_display.cpp.
| void motion_planning_rviz_plugin::PlanningDisplay::update | ( | float | wall_dt, | |
| float | ros_dt | |||
| ) | [virtual] |
Reimplemented from rviz::Display.
Definition at line 275 of file planning_display.cpp.
float motion_planning_rviz_plugin::PlanningDisplay::alpha_ [protected] |
Definition at line 190 of file planning_display.h.
rviz::FloatPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::alpha_property_ [protected] |
Definition at line 197 of file planning_display.h.
bool motion_planning_rviz_plugin::PlanningDisplay::animating_path_ [protected] |
Definition at line 185 of file planning_display.h.
rviz::BoolPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::collision_enabled_property_ [protected] |
Definition at line 193 of file planning_display.h.
int motion_planning_rviz_plugin::PlanningDisplay::current_state_ [protected] |
Definition at line 186 of file planning_display.h.
float motion_planning_rviz_plugin::PlanningDisplay::current_state_time_ [protected] |
Definition at line 189 of file planning_display.h.
std::string motion_planning_rviz_plugin::PlanningDisplay::description_param_ [protected] |
ROS parameter that contains the robot xml description.
Definition at line 174 of file planning_display.h.
arm_navigation_msgs::DisplayTrajectory::ConstPtr motion_planning_rviz_plugin::PlanningDisplay::displaying_kinematic_path_message_ [protected] |
Definition at line 183 of file planning_display.h.
planning_environment::RobotModels* motion_planning_rviz_plugin::PlanningDisplay::env_models_ [protected] |
Definition at line 180 of file planning_display.h.
arm_navigation_msgs::DisplayTrajectory::ConstPtr motion_planning_rviz_plugin::PlanningDisplay::incoming_kinematic_path_message_ [protected] |
Definition at line 182 of file planning_display.h.
const planning_models::KinematicModel* motion_planning_rviz_plugin::PlanningDisplay::kinematic_model_ [protected] |
Definition at line 181 of file planning_display.h.
std::string motion_planning_rviz_plugin::PlanningDisplay::kinematic_path_topic_ [protected] |
Definition at line 179 of file planning_display.h.
bool motion_planning_rviz_plugin::PlanningDisplay::loop_display_ [protected] |
Definition at line 187 of file planning_display.h.
rviz::BoolPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::loop_display_property_ [protected] |
Definition at line 198 of file planning_display.h.
bool motion_planning_rviz_plugin::PlanningDisplay::new_kinematic_path_ [protected] |
Definition at line 184 of file planning_display.h.
Handles actually drawing the robot.
Definition at line 176 of file planning_display.h.
rviz::StringPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::robot_description_property_ [protected] |
Definition at line 195 of file planning_display.h.
float motion_planning_rviz_plugin::PlanningDisplay::state_display_time_ [protected] |
Definition at line 188 of file planning_display.h.
rviz::FloatPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::state_display_time_property_ [protected] |
Definition at line 194 of file planning_display.h.
Definition at line 200 of file planning_display.h.
Definition at line 178 of file planning_display.h.
rviz::ROSTopicStringPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::topic_property_ [protected] |
Definition at line 196 of file planning_display.h.
rviz::BoolPropertyWPtr motion_planning_rviz_plugin::PlanningDisplay::visual_enabled_property_ [protected] |
Definition at line 192 of file planning_display.h.