base_module.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Author: Zerom */
18 
19 #ifndef BASE_MODULE_H_
20 #define BASE_MODULE_H_
21 
22 #include <ros/ros.h>
23 #include <ros/callback_queue.h>
24 #include <std_msgs/Empty.h>
25 #include <std_msgs/String.h>
26 #include <std_msgs/Int32.h>
27 #include <sensor_msgs/JointState.h>
28 #include <boost/thread.hpp>
29 
30 #include "rh_p12_rn_base_module_msgs/GetItemValue.h"
31 #include "robotis_controller_msgs/SyncWriteItem.h"
33 
34 namespace rh_p12_rn
35 {
36 
37 class BaseModule
39  public robotis_framework::Singleton<BaseModule>
40 {
41 private:
43  boost::thread queue_thread_;
44 
46 
52  bool is_moving_;
56 
57  /* subscriber & publisher */
60 
61  void queueThread();
62 
63 public:
64  BaseModule();
65  virtual ~BaseModule();
66 
67  /* ROS Topic Callback Functions */
68  void setPosition(const robotis_controller_msgs::SyncWriteItem::ConstPtr &msg);
69 
70  /* ROS Service Callback Functions */
71  bool getItemValueCallback(rh_p12_rn_base_module_msgs::GetItemValue::Request &req,
72  rh_p12_rn_base_module_msgs::GetItemValue::Response &res);
73 
74  void initialize(const int control_cycle_msec, robotis_framework::Robot *robot);
75  void process(std::map<std::string, robotis_framework::Dynamixel *> dxls, std::map<std::string, double> sensors);
76 
77  void stop();
78  bool isRunning();
79 };
80 
81 }
82 
83 #endif /* BASE_MODULE_H_ */
ros::Publisher present_current_pub_
Definition: base_module.h:59
void setPosition(const robotis_controller_msgs::SyncWriteItem::ConstPtr &msg)
Definition: base_module.cpp:88
boost::thread queue_thread_
Definition: base_module.h:43
ros::Publisher present_position_pub_
Definition: base_module.h:58
void process(std::map< std::string, robotis_framework::Dynamixel * > dxls, std::map< std::string, double > sensors)
robotis_framework::Robot * robot_
Definition: base_module.h:45
void initialize(const int control_cycle_msec, robotis_framework::Robot *robot)
Definition: base_module.cpp:50
bool getItemValueCallback(rh_p12_rn_base_module_msgs::GetItemValue::Request &req, rh_p12_rn_base_module_msgs::GetItemValue::Response &res)
Definition: base_module.cpp:97


rh_p12_rn_base_module
Author(s): Zerom
autogenerated on Mon Jun 10 2019 14:42:05