19 #ifndef DDS_ROS_BRIDGE_ROS_PAYLOAD_STATE_H_
20 #define DDS_ROS_BRIDGE_ROS_PAYLOAD_STATE_H_
26 #include "dds_ros_bridge/ros_sub_rapid_pub.h"
27 #include "dds_ros_bridge/util.h"
29 #include "ff_hw_msgs/EpsPowerState.h"
30 #include "ff_hw_msgs/EpsPowerStateValue.h"
32 #include "knDds/DdsTypedSupplier.h"
34 #include "rapidUtil/RapidHelper.h"
36 #include "dds_msgs/AstrobeeConstants.h"
37 #include "dds_msgs/PayloadConfigSupport.h"
38 #include "dds_msgs/PayloadStateSupport.h"
45 const std::string& pub_topic,
46 const ros::NodeHandle &nh,
47 const unsigned int queue_size = 10);
49 void Callback(ff_hw_msgs::EpsPowerStateConstPtr
const&
state);
53 kn::DdsTypedSupplier<rapid::ext::astrobee::PayloadState>;
54 using StateSupplierPtr = std::unique_ptr<StateSupplier>;
56 StateSupplierPtr state_supplier_;
58 using ConfigSupplier =
59 kn::DdsTypedSupplier<rapid::ext::astrobee::PayloadConfig>;
60 using ConfigSupplierPtr = std::unique_ptr<ConfigSupplier>;
62 ConfigSupplierPtr config_supplier_;
67 #endif // DDS_ROS_BRIDGE_ROS_PAYLOAD_STATE_H_