23 #include <packml_msgs/GetStats.h> 24 #include <packml_msgs/ResetStats.h> 25 #include <packml_msgs/Transition.h> 26 #include <packml_msgs/Status.h> 42 std::shared_ptr<packml_sm::AbstractStateMachine>
sm_;
49 bool transRequest(packml_msgs::Transition::Request& req, packml_msgs::Transition::Response& res);
54 bool getStats(packml_msgs::GetStats::Request& req, packml_msgs::GetStats::Response& response);
55 bool resetStats(packml_msgs::ResetStats::Request& req, packml_msgs::ResetStats::Response& response);
59 #endif // PACKML_ROS_H std::shared_ptr< packml_sm::AbstractStateMachine > sm_
packml_msgs::Status status_msg_
ros::Publisher status_pub_
ros::ServiceServer get_stats_server_
ros::ServiceServer reset_stats_server_
PackmlRos(ros::NodeHandle nh, ros::NodeHandle pn, std::shared_ptr< packml_sm::AbstractStateMachine > sm)
void getCurrentStats(packml_msgs::Stats &out_stats)
bool getStats(packml_msgs::GetStats::Request &req, packml_msgs::GetStats::Response &response)
void handleStateChanged(packml_sm::AbstractStateMachine &state_machine, const packml_sm::StateChangedEventArgs &args)
bool transRequest(packml_msgs::Transition::Request &req, packml_msgs::Transition::Response &res)
ros::ServiceServer trans_server_
bool resetStats(packml_msgs::ResetStats::Request &req, packml_msgs::ResetStats::Response &response)