qnode.hpp
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 /* Authors: Kayman Jung, SCH */
18 
19 /*****************************************************************************
20  ** Ifdefs
21  *****************************************************************************/
22 
23 #ifndef thormang3_offset_tuner_client_QNODE_HPP_
24 #define thormang3_offset_tuner_client_QNODE_HPP_
25 
26 /*****************************************************************************
27  ** Includes
28  *****************************************************************************/
29 #ifndef Q_MOC_RUN
30 
31 #include <string>
32 #include <QThread>
33 #include <QStringListModel>
34 
35 #include <ros/ros.h>
36 #include <ros/package.h>
37 #include <std_msgs/String.h>
38 #include <yaml-cpp/yaml.h>
39 
40 #include "thormang3_offset_tuner_msgs/JointOffsetData.h"
41 #include "thormang3_offset_tuner_msgs/JointOffsetPositionData.h"
42 #include "thormang3_offset_tuner_msgs/JointTorqueOnOff.h"
43 #include "thormang3_offset_tuner_msgs/JointTorqueOnOffArray.h"
44 #include "thormang3_offset_tuner_msgs/GetPresentJointOffsetData.h"
45 
46 #endif // Q_MOC_RUN
47 
48 /*****************************************************************************
49  ** Namespaces
50  *****************************************************************************/
51 
53 {
54 
55 /*****************************************************************************
56  ** Class
57  *****************************************************************************/
58 
59 class QNode : public QThread
60 {
61 Q_OBJECT
62  public:
63  enum LogLevel
64  {
70  };
71  QNode(int argc, char** argv);
72  virtual ~QNode();
73  bool init();
74  bool init(const std::string &master_url, const std::string &host_url);
75  void run();
76 
77  QStringListModel* loggingModel()
78  {
79  return &logging_model_;
80  }
81  void log(const LogLevel &level, const std::string &msg);
82 
83  void send_torque_enable_msg(thormang3_offset_tuner_msgs::JointTorqueOnOffArray msg);
84  void send_joint_offset_data_msg(thormang3_offset_tuner_msgs::JointOffsetData msg);
85  void send_command_msg(std_msgs::String msg);
86  bool is_refresh()
87  {
88  return is_refresh_;
89  }
90 
91  std::map<int, std::string> right_arm_offset_group;
92  std::map<int, std::string> left_arm_offset_group;
93  std::map<int, std::string> legs_offset_group;
94  std::map<int, std::string> body_offset_group;
95 
96  public Q_SLOTS:
98 
99 Q_SIGNALS:
100  void loggingUpdated();
101  void rosShutdown();
102 
103  void update_present_joint_offset_data(thormang3_offset_tuner_msgs::JointOffsetPositionData msg);
104 
105  private:
106  void ParseOffsetGroup(const std::string &path);
107 
109  char** init_argv_;
111  QStringListModel logging_model_;
112 
116 
118 };
119 
120 } // namespace thormang3_offset_tuner_client
121 
122 #endif /* thormang3_offset_tuner_client_QNODE_HPP_ */
void send_command_msg(std_msgs::String msg)
Definition: qnode.cpp:112
QNode(int argc, char **argv)
Definition: qnode.cpp:43
void log(const LogLevel &level, const std::string &msg)
Definition: qnode.cpp:146
std::map< int, std::string > right_arm_offset_group
Definition: qnode.hpp:91
void ParseOffsetGroup(const std::string &path)
Definition: qnode.cpp:188
std::map< int, std::string > body_offset_group
Definition: qnode.hpp:94
std::map< int, std::string > left_arm_offset_group
Definition: qnode.hpp:92
void send_torque_enable_msg(thormang3_offset_tuner_msgs::JointTorqueOnOffArray msg)
Definition: qnode.cpp:98
ros::ServiceClient get_present_joint_offset_data_client_
Definition: qnode.hpp:117
QStringListModel * loggingModel()
Definition: qnode.hpp:77
void send_joint_offset_data_msg(thormang3_offset_tuner_msgs::JointOffsetData msg)
Definition: qnode.cpp:105
std::map< int, std::string > legs_offset_group
Definition: qnode.hpp:93
ros::Publisher joint_offset_data_pub_
Definition: qnode.hpp:113
void update_present_joint_offset_data(thormang3_offset_tuner_msgs::JointOffsetPositionData msg)


thormang3_offset_tuner_client
Author(s): Kayman
autogenerated on Mon Jun 10 2019 15:38:36