5 #ifndef MULTI_ROBOT_INFO_DISPLAY_H 6 #define MULTI_ROBOT_INFO_DISPLAY_H 13 #include <geometry_msgs/PoseWithCovariance.h> 15 #include <tuw_multi_robot_msgs/RobotInfo.h> 36 class MultiRobotInfoVisual;
50 void callbackRobotInfo(
const tuw_multi_robot_msgs::RobotInfoConstPtr &msg );
57 virtual void onInitialize();
65 void updateScalePose();
66 void updateColorPose();
67 void updateBoolProperty();
68 void onKeepAliveChanged();
69 void onKeepMeasurementsChanged();
73 void processMessage(
const tuw_multi_robot_msgs::RobotInfoConstPtr &msg );
76 std::shared_ptr<MultiRobotInfoVisual> visual_ =
nullptr;
91 #endif // POSE_WITH_COVARIANCE_DISPLAY_H
std::map< std::string, std::shared_ptr< rviz::BoolProperty > > bool_properties_
std::shared_ptr< rviz::IntProperty > keep_alive_
std::shared_ptr< rviz::ColorProperty > property_color_pose_
std::shared_ptr< rviz::IntProperty > keep_measurements_
std::shared_ptr< rviz::Property > robot_bool_properties_
ros::Subscriber sub_robot_info_
std::shared_ptr< rviz::FloatProperty > property_scale_pose_