// ****************************************************************************************** // Base class contructor // ****************************************************************************************** RobotStateDisplay::RobotStateDisplay() : Display(), update_state_(false) { robot_description_property_ = new rviz::StringProperty( "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded", this, SLOT( changedRobotDescription() ), this ); robot_state_topic_property_ = new rviz::RosTopicProperty( "Robot State Topic", "display_robot_state", ros::message_traits::datatype<moveit_msgs::DisplayRobotState>(), "The topic on which the moveit_msgs::RobotState messages are received", this, SLOT( changedRobotStateTopic() ), this ); // Planning scene category ------------------------------------------------------------------------------------------- root_link_name_property_ = new rviz::StringProperty( "Robot Root Link", "", "Shows the name of the root link for the robot model", this, SLOT( changedRootLinkName() ), this ); root_link_name_property_->setReadOnly(true); robot_alpha_property_ = new rviz::FloatProperty( "Robot Alpha", 1.0f, "Specifies the alpha for the robot links", this, SLOT( changedRobotSceneAlpha() ), this ); robot_alpha_property_->setMin( 0.0 ); robot_alpha_property_->setMax( 1.0 ); attached_body_color_property_ = new rviz::ColorProperty( "Attached Body Color", QColor(150, 50, 150), "The color for the attached bodies", this, SLOT( changedAttachedBodyColor() ), this ); enable_link_highlight_ = new rviz::BoolProperty("Show Highlights", true, "Specifies whether link highlighting is enabled", this, SLOT( changedEnableLinkHighlight() ), this); enable_visual_visible_ = new rviz::BoolProperty("Visual Enabled", true, "Whether to display the visual representation of the robot.", this, SLOT( changedEnableVisualVisible() ), this); enable_collision_visible_ = new rviz::BoolProperty("Collision Enabled", false, "Whether to display the collision representation of the robot.", this, SLOT( changedEnableCollisionVisible() ), this); show_all_links_ = new rviz::BoolProperty("Show All Links", true, "Toggle all links visibility on or off.", this, SLOT( changedAllLinks() ), this); }
// ****************************************************************************************** // Base class contructor // ****************************************************************************************** PlanningSceneDisplay::PlanningSceneDisplay() : Display(), current_scene_time_(0.0f), planning_scene_needs_render_(true) { robot_description_property_ = new rviz::StringProperty( "Robot Description", "robot_description", "The name of the ROS parameter where the URDF for the robot is loaded", this, SLOT( changedRobotDescription() ), this ); planning_scene_topic_property_ = new rviz::RosTopicProperty( "Planning Scene Topic", "planning_scene", ros::message_traits::datatype<moveit_msgs::PlanningScene>(), "The topic on which the moveit_msgs::PlanningScene messages are received", this, SLOT( changedPlanningSceneTopic() ), this ); // Category Groups scene_category_ = new rviz::Property( "Scene Geometry", QVariant(), "", this ); robot_category_ = new rviz::Property( "Scene Robot", QVariant(), "", this ); // Planning scene category ------------------------------------------------------------------------------------------- scene_name_property_ = new rviz::StringProperty( "Scene Name", "(noname)", "Shows the name of the planning scene", scene_category_, SLOT( changedSceneName() ), this ); scene_name_property_->setShouldBeSaved(false); scene_enabled_property_ = new rviz::BoolProperty( "Show Scene Geometry", true, "Indicates whether planning scenes should be displayed", scene_category_, SLOT( changedSceneEnabled() ), this ); scene_alpha_property_ = new rviz::FloatProperty( "Scene Alpha", 0.9f, "Specifies the alpha for the robot links", scene_category_, SLOT( changedSceneAlpha() ), this ); scene_alpha_property_->setMin( 0.0 ); scene_alpha_property_->setMax( 1.0 ); scene_color_property_ = new rviz::ColorProperty( "Scene Color", QColor(50, 230, 50), "The color for the planning scene obstacles (if a color is not defined)", scene_category_, SLOT( changedSceneColor() ), this ); octree_render_property_ = new rviz::EnumProperty( "Voxel Rendering", "Occupied Voxels", "Select voxel type.", scene_category_, SLOT( changedOctreeRenderMode() ), this ); octree_render_property_->addOption( "Occupied Voxels", OCTOMAP_OCCUPIED_VOXELS ); octree_render_property_->addOption( "Free Voxels", OCTOMAP_FREE_VOXELS ); octree_render_property_->addOption( "All Voxels", OCTOMAP_FREE_VOXELS | OCTOMAP_OCCUPIED_VOXELS); octree_coloring_property_ = new rviz::EnumProperty( "Voxel Coloring", "Z-Axis", "Select voxel coloring mode", scene_category_, SLOT( changedOctreeColorMode() ), this ); octree_coloring_property_->addOption( "Z-Axis", OCTOMAP_Z_AXIS_COLOR ); octree_coloring_property_->addOption( "Cell Probability", OCTOMAP_PROBABLILTY_COLOR ); root_link_name_property_ = new rviz::StringProperty( "Robot Root Link", "", "Shows the name of the root link for the robot model", robot_category_, SLOT( changedRootLinkName() ), this ); root_link_name_property_->setReadOnly(true); scene_robot_enabled_property_ = new rviz::BoolProperty( "Show Scene Robot", true, "Indicates whether the robot state specified by the planning scene should be displayed", robot_category_, SLOT( changedSceneRobotEnabled() ), this ); robot_alpha_property_ = new rviz::FloatProperty( "Robot Alpha", 0.5f, "Specifies the alpha for the robot links", robot_category_, SLOT( changedRobotSceneAlpha() ), this ); robot_alpha_property_->setMin( 0.0 ); robot_alpha_property_->setMax( 1.0 ); attached_body_color_property_ = new rviz::ColorProperty( "Attached Body Color", QColor(150, 50, 150), "The color for the attached bodies", robot_category_, SLOT( changedAttachedBodyColor() ), this ); scene_display_time_property_ = new rviz::FloatProperty( "Scene Display Time", 0.2f, "The amount of wall-time to wait in between rendering updates to the planning scene (if any)", scene_category_, SLOT( changedSceneDisplayTime() ), this ); scene_display_time_property_->setMin(0.0001); }