qnode.hpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2016 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: Taehun Lim (Darby) */
18 
19 #ifndef DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP
20 #define DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP
21 
22 #ifndef Q_MOC_RUN
23 
24 #include <ros/ros.h>
25 #include <string>
26 #include <QThread>
27 #include <QStringListModel>
28 #include <pthread.h>
29 
30 #include "message_header.h"
31 
32 #include "dynamixel_workbench_msgs/DynamixelCommand.h"
33 #include "dynamixel_workbench_msgs/GetDynamixelInfo.h"
34 #include "dynamixel_workbench_msgs/DynamixelInfo.h"
35 
36 #endif
37 
38 namespace qnode
39 {
40 class QNode : public QThread
41 {
42  Q_OBJECT
43 
44  public:
45  QNode(int argc, char** argv );
46  virtual ~QNode();
47 
48  bool init();
49  void run();
50 
51  QStringListModel* loggingModel() { return &logging_model_; }
52  void log(const std::string &msg, int64_t sender);
53  void log(const std::string &msg);
54 
55  // TODO : Add new Dynamixel
56  void AXStatusMsgCallback(const dynamixel_workbench_msgs::AX::ConstPtr &msg);
57 
58  void RXStatusMsgCallback(const dynamixel_workbench_msgs::RX::ConstPtr &msg);
59 
60  void MXStatusMsgCallback(const dynamixel_workbench_msgs::MX::ConstPtr &msg);
61  void MXExtStatusMsgCallback(const dynamixel_workbench_msgs::MXExt::ConstPtr &msg);
62  void MX2StatusMsgCallback(const dynamixel_workbench_msgs::MX2::ConstPtr &msg);
63  void MX2ExtStatusMsgCallback(const dynamixel_workbench_msgs::MX2Ext::ConstPtr &msg);
64 
65  void EXStatusMsgCallback(const dynamixel_workbench_msgs::EX::ConstPtr &msg);
66 
67  void XL320StatusMsgCallback(const dynamixel_workbench_msgs::XL320::ConstPtr &msg);
68  void XLStatusMsgCallback(const dynamixel_workbench_msgs::XL::ConstPtr &msg);
69 
70  void XMStatusMsgCallback(const dynamixel_workbench_msgs::XM::ConstPtr &msg);
71  void XMExtStatusMsgCallback(const dynamixel_workbench_msgs::XMExt::ConstPtr &msg);
72 
73  void XHStatusMsgCallback(const dynamixel_workbench_msgs::XH::ConstPtr &msg);
74 
75  void PROStatusMsgCallback(const dynamixel_workbench_msgs::PRO::ConstPtr &msg);
76  void PROExtStatusMsgCallback(const dynamixel_workbench_msgs::PROExt::ConstPtr &msg);
77 
78  void AX(void);
79 
80  void RX();
81 
82  void MX();
83  void MXExt();
84  void MX2();
85  void MX2Ext();
86 
87  void EX();
88 
89  void XL320();
90  void XL();
91 
92  void XM();
93  void XMExt();
94 
95  void XH();
96 
97  void PRO();
98  void PROExt();
99 
101 
102  bool sendSetIdMsg(uint8_t set_id);
103  bool sendSetOperatingModeMsg(std::string index, float protocol_version, std::string model_name, int32_t value_of_max_radian_position);
104  bool sendSetBaudrateMsg(int64_t baud_rate);
105 
106  bool sendTorqueMsg(int64_t onoff);
107  bool sendRebootMsg(void);
108  bool sendResetMsg(void);
109  bool sendAddressValueMsg(std::string addr_name, int64_t value);
110  bool setPositionZeroMsg(int32_t zero_position);
111 
113 
114  void getDynamixelInfo();
115  // TODO : Add new Dynamixel
117  bool sendCommandMsg(std::string cmd, std::string addr = "", int64_t value = 0);
118 
119  Q_SIGNALS:
120  void rosShutdown();
121 
122  void updateDynamixelInfo(dynamixel_workbench_msgs::DynamixelInfo);
123 
124  private:
126  char** init_argv;
127  pthread_mutex_t mutex;
128 
129  QStringListModel logging_model_;
130 
131  // ROS Topic Publisher
132 
133  // ROS Topic Subscriber
135 
136  // ROS Service Server
137 
138  // ROS Service Client
141 
142  // Single Manager GUI variable
143  int64_t row_count_;
144 
145  dynamixel_workbench_msgs::DynamixelInfo dynamixel_info_;
146  dynamixel_workbench_msgs::AX ax_msgs_;
147  dynamixel_workbench_msgs::RX rx_msgs_;
148  dynamixel_workbench_msgs::MX mx_msgs_;
149  dynamixel_workbench_msgs::MXExt mxext_msgs_;
150  dynamixel_workbench_msgs::MX2 mx2_msgs_;
151  dynamixel_workbench_msgs::MX2Ext mx2ext_msgs_;
152  dynamixel_workbench_msgs::EX ex_msgs_;
153  dynamixel_workbench_msgs::XL320 xl320_msgs_;
154  dynamixel_workbench_msgs::XL xl_msgs_;
155  dynamixel_workbench_msgs::XM xm_msgs_;
156  dynamixel_workbench_msgs::XMExt xmext_msgs_;
157  dynamixel_workbench_msgs::XH xh_msgs_;
158  dynamixel_workbench_msgs::PRO pro_msgs_;
159  dynamixel_workbench_msgs::PROExt proext_msgs_;
160 };
161 }
162 
163 #endif //DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP
dynamixel_workbench_msgs::XL xl_msgs_
Definition: qnode.hpp:154
bool sendResetMsg(void)
Definition: qnode.cpp:360
void PROStatusMsgCallback(const dynamixel_workbench_msgs::PRO::ConstPtr &msg)
Definition: qnode.cpp:1317
void EXStatusMsgCallback(const dynamixel_workbench_msgs::EX::ConstPtr &msg)
Definition: qnode.cpp:1275
dynamixel_workbench_msgs::XH xh_msgs_
Definition: qnode.hpp:157
void MX2Ext()
Definition: qnode.cpp:771
void PROExtStatusMsgCallback(const dynamixel_workbench_msgs::PROExt::ConstPtr &msg)
Definition: qnode.cpp:1324
dynamixel_workbench_msgs::PROExt proext_msgs_
Definition: qnode.hpp:159
QStringListModel logging_model_
Definition: qnode.hpp:129
ros::ServiceClient dynamixel_info_client_
Definition: qnode.hpp:139
void XM()
Definition: qnode.cpp:963
void XL320()
Definition: qnode.cpp:869
void XL()
Definition: qnode.cpp:907
void MX2()
Definition: qnode.cpp:715
dynamixel_workbench_msgs::MXExt mxext_msgs_
Definition: qnode.hpp:149
int64_t row_count_
Definition: qnode.hpp:143
void PRO()
Definition: qnode.cpp:1140
dynamixel_workbench_msgs::EX ex_msgs_
Definition: qnode.hpp:152
void XLStatusMsgCallback(const dynamixel_workbench_msgs::XL::ConstPtr &msg)
Definition: qnode.cpp:1289
Definition: qnode.hpp:38
bool sendRebootMsg(void)
Definition: qnode.cpp:352
void AX(void)
Definition: qnode.cpp:552
bool sendCommandMsg(std::string cmd, std::string addr="", int64_t value=0)
Definition: qnode.cpp:70
ros::ServiceClient dynamixel_command_client_
Definition: qnode.hpp:140
dynamixel_workbench_msgs::AX ax_msgs_
Definition: qnode.hpp:146
void run()
Definition: qnode.cpp:500
void RXStatusMsgCallback(const dynamixel_workbench_msgs::RX::ConstPtr &msg)
Definition: qnode.cpp:1240
QNode(int argc, char **argv)
Definition: qnode.cpp:29
void XH()
Definition: qnode.cpp:1082
void XMExtStatusMsgCallback(const dynamixel_workbench_msgs::XMExt::ConstPtr &msg)
Definition: qnode.cpp:1303
void XMStatusMsgCallback(const dynamixel_workbench_msgs::XM::ConstPtr &msg)
Definition: qnode.cpp:1296
void PROExt()
Definition: qnode.cpp:1186
void log(const std::string &msg, int64_t sender)
Definition: qnode.cpp:514
void RX()
Definition: qnode.cpp:591
void MX2StatusMsgCallback(const dynamixel_workbench_msgs::MX2::ConstPtr &msg)
Definition: qnode.cpp:1261
dynamixel_workbench_msgs::XL320 xl320_msgs_
Definition: qnode.hpp:153
int init_argc
Definition: qnode.hpp:125
QStringListModel * loggingModel()
Definition: qnode.hpp:51
char ** init_argv
Definition: qnode.hpp:126
void MXExt()
Definition: qnode.cpp:671
dynamixel_workbench_msgs::MX mx_msgs_
Definition: qnode.hpp:148
dynamixel_workbench_msgs::PRO pro_msgs_
Definition: qnode.hpp:158
void rosShutdown()
bool sendSetBaudrateMsg(int64_t baud_rate)
Definition: qnode.cpp:95
dynamixel_workbench_msgs::XM xm_msgs_
Definition: qnode.hpp:155
void MX()
Definition: qnode.cpp:630
dynamixel_workbench_msgs::RX rx_msgs_
Definition: qnode.hpp:147
dynamixel_workbench_msgs::DynamixelInfo dynamixel_info_
Definition: qnode.hpp:145
bool sendAddressValueMsg(std::string addr_name, int64_t value)
Definition: qnode.cpp:381
void XMExt()
Definition: qnode.cpp:1021
void getDynamixelInfo()
Definition: qnode.cpp:389
pthread_mutex_t mutex
Definition: qnode.hpp:127
void initDynamixelStateSubscriber()
Definition: qnode.cpp:407
void MX2ExtStatusMsgCallback(const dynamixel_workbench_msgs::MX2Ext::ConstPtr &msg)
Definition: qnode.cpp:1268
void(qnode::QNode::* dynamixelDataLogPtr)(void)
Definition: qnode.hpp:100
dynamixel_workbench_msgs::MX2 mx2_msgs_
Definition: qnode.hpp:150
void XL320StatusMsgCallback(const dynamixel_workbench_msgs::XL320::ConstPtr &msg)
Definition: qnode.cpp:1282
bool init()
Definition: qnode.cpp:45
bool sendTorqueMsg(int64_t onoff)
Definition: qnode.cpp:344
void MXStatusMsgCallback(const dynamixel_workbench_msgs::MX::ConstPtr &msg)
Definition: qnode.cpp:1247
void MXExtStatusMsgCallback(const dynamixel_workbench_msgs::MXExt::ConstPtr &msg)
Definition: qnode.cpp:1254
void updateDynamixelInfo(dynamixel_workbench_msgs::DynamixelInfo)
ros::Subscriber dynamixel_status_msg_sub_
Definition: qnode.hpp:134
dynamixel_workbench_msgs::MX2Ext mx2ext_msgs_
Definition: qnode.hpp:151
void EX()
Definition: qnode.cpp:828
dynamixel_workbench_msgs::XMExt xmext_msgs_
Definition: qnode.hpp:156
bool sendSetIdMsg(uint8_t set_id)
Definition: qnode.cpp:87
void AXStatusMsgCallback(const dynamixel_workbench_msgs::AX::ConstPtr &msg)
Definition: qnode.cpp:1233
void writeReceivedDynamixelData()
Definition: qnode.cpp:544
virtual ~QNode()
Definition: qnode.cpp:35
void XHStatusMsgCallback(const dynamixel_workbench_msgs::XH::ConstPtr &msg)
Definition: qnode.cpp:1310
bool sendSetOperatingModeMsg(std::string index, float protocol_version, std::string model_name, int32_t value_of_max_radian_position)
Definition: qnode.cpp:103
bool setPositionZeroMsg(int32_t zero_position)
Definition: qnode.cpp:373


dynamixel_workbench_single_manager_gui
Author(s): Darby Lim
autogenerated on Mon Jun 10 2019 13:06:16