packml_ros.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (Apache License)
3  *
4  * Copyright (c) 2017 Shaun Edwards
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 #ifndef PACKML_ROS_H
19 #define PACKML_ROS_H
20 
21 #include <ros/ros.h>
22 
23 #include <packml_msgs/GetStats.h>
24 #include <packml_msgs/ResetStats.h>
25 #include <packml_msgs/Transition.h>
26 #include <packml_msgs/Status.h>
28 
29 namespace packml_ros
30 {
31 class PackmlRos
32 {
33 public:
34  PackmlRos(ros::NodeHandle nh, ros::NodeHandle pn, std::shared_ptr<packml_sm::AbstractStateMachine> sm);
35  ~PackmlRos();
36  void spin();
37  void spinOnce();
38 
39 protected:
42  std::shared_ptr<packml_sm::AbstractStateMachine> sm_;
47  packml_msgs::Status status_msg_;
48 
49  bool transRequest(packml_msgs::Transition::Request& req, packml_msgs::Transition::Response& res);
50 
51 private:
53  void getCurrentStats(packml_msgs::Stats& out_stats);
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);
56 };
57 } // namespace packml_ros
58 
59 #endif // PACKML_ROS_H
std::shared_ptr< packml_sm::AbstractStateMachine > sm_
Definition: packml_ros.h:42
packml_msgs::Status status_msg_
Definition: packml_ros.h:47
ros::Publisher status_pub_
Definition: packml_ros.h:43
ros::ServiceServer get_stats_server_
Definition: packml_ros.h:46
ros::ServiceServer reset_stats_server_
Definition: packml_ros.h:45
PackmlRos(ros::NodeHandle nh, ros::NodeHandle pn, std::shared_ptr< packml_sm::AbstractStateMachine > sm)
Definition: packml_ros.cpp:27
ros::NodeHandle nh_
Definition: packml_ros.h:40
void getCurrentStats(packml_msgs::Stats &out_stats)
Definition: packml_ros.cpp:159
ros::NodeHandle pn_
Definition: packml_ros.h:41
bool getStats(packml_msgs::GetStats::Request &req, packml_msgs::GetStats::Response &response)
Definition: packml_ros.cpp:202
void handleStateChanged(packml_sm::AbstractStateMachine &state_machine, const packml_sm::StateChangedEventArgs &args)
Definition: packml_ros.cpp:139
bool transRequest(packml_msgs::Transition::Request &req, packml_msgs::Transition::Response &res)
Definition: packml_ros.cpp:67
ros::ServiceServer trans_server_
Definition: packml_ros.h:44
bool resetStats(packml_msgs::ResetStats::Request &req, packml_msgs::ResetStats::Response &response)
Definition: packml_ros.cpp:211


packml_ros
Author(s): Shaun Edwards
autogenerated on Fri Jul 12 2019 03:31:00