20 #ifndef DDS_ROS_BRIDGE_ROS_DISK_STATE_H_
21 #define DDS_ROS_BRIDGE_ROS_DISK_STATE_H_
27 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
28 #include "dds_ros_bridge/util.h"
30 #include "ff_msgs/DiskState.h"
31 #include "ff_msgs/DiskStateStamped.h"
33 #include "knDds/DdsTypedSupplier.h"
35 #include "rapidUtil/RapidHelper.h"
37 #include "dds_msgs/AstrobeeConstants.h"
38 #include "dds_msgs/DiskStateSupport.h"
39 #include "dds_msgs/DiskConfigSupport.h"
46 const std::string& pub_topic,
47 const ros::NodeHandle &nh,
48 const unsigned int queue_size = 10);
50 void Callback(ff_msgs::DiskStateStampedConstPtr
const&
state);
59 kn::DdsTypedSupplier<rapid::ext::astrobee::DiskState>;
60 using StateSupplierPtr = std::unique_ptr<StateSupplier>;
62 StateSupplierPtr state_supplier_;
64 using ConfigSupplier =
65 kn::DdsTypedSupplier<rapid::ext::astrobee::DiskConfig>;
66 using ConfigSupplierPtr = std::unique_ptr<ConfigSupplier>;
68 ConfigSupplierPtr config_supplier_;
72 unsigned int llp_disk_size_, mlp_disk_size_, hlp_disk_size_;
74 ff_msgs::DiskStateStampedConstPtr llp_state_, mlp_state_, hlp_state_;
76 ros::Timer pub_timer_;
81 #endif // DDS_ROS_BRIDGE_ROS_DISK_STATE_H_