qnode.cpp
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 #include <ros/ros.h>
20 #include <ros/network.h>
21 
22 #include <string>
23 #include <sstream>
24 #include <std_msgs/String.h>
25 #include "../include/dynamixel_workbench_single_manager_gui/qnode.hpp"
26 
27 using namespace qnode;
28 
29 QNode::QNode(int argc, char** argv )
30  :init_argc(argc),
31  init_argv(argv),
32  row_count_(0)
33 {}
34 
36 {
37  if(ros::isStarted())
38  {
39  ros::shutdown();
41  }
42  wait();
43 }
44 
46 {
47  ros::init(init_argc,init_argv,"single_manager_gui");
48 
49  if (!ros::master::check())
50  return false;
51 
52  ros::start();
53  ros::NodeHandle node_handle;
54 
55  // Init Service Client
56  dynamixel_info_client_ = node_handle.serviceClient<dynamixel_workbench_msgs::GetDynamixelInfo>("dynamixel/info");
57  dynamixel_command_client_ = node_handle.serviceClient<dynamixel_workbench_msgs::DynamixelCommand>("dynamixel/command");
59 
60  // Init Message Subscriber
62 
63  // Init mutex
64  mutex = PTHREAD_MUTEX_INITIALIZER;
65 
66  start();
67  return true;
68 }
69 
70 bool QNode::sendCommandMsg(std::string cmd, std::string addr, int64_t value)
71 {
72  dynamixel_workbench_msgs::DynamixelCommand set_dynamixel_command;
73 
74  set_dynamixel_command.request.command = cmd;
75  set_dynamixel_command.request.addr_name = addr;
76  set_dynamixel_command.request.value = value;
77 
78  if (dynamixel_command_client_.call(set_dynamixel_command))
79  {
80  if (!set_dynamixel_command.response.comm_result)
81  return false;
82  else
83  return true;
84  }
85 }
86 
87 bool QNode::sendSetIdMsg(uint8_t set_id)
88 {
89  if (sendCommandMsg("addr", "ID", set_id))
90  return true;
91  else
92  return false;
93 }
94 
95 bool QNode::sendSetBaudrateMsg(int64_t baud_rate)
96 {
97  if (sendCommandMsg("addr", "Baud_Rate", baud_rate))
98  return true;
99  else
100  return false;
101 }
102 
103 bool QNode::sendSetOperatingModeMsg(std::string index, float protocol_version, std::string model_name, int32_t value_of_max_radian_position)
104 {
105  dynamixel_workbench_msgs::DynamixelCommand set_dynamixel_command;
106 
107  if (protocol_version == 1.0)
108  {
109  if (index == "position_control")
110  {
111  if (sendCommandMsg("addr", "CW_Angle_Limit", 0) && sendCommandMsg("addr", "CCW_Angle_Limit", value_of_max_radian_position))
112  return true;
113  else
114  return false;
115  }
116  else if (index == "velocity_control")
117  {
118  if (sendCommandMsg("addr", "CW_Angle_Limit", 0) && sendCommandMsg("addr", "CCW_Angle_Limit", 0))
119  return true;
120  else
121  return false;
122  }
123  else if (index == "extended_position_control")
124  {
125  if (sendCommandMsg("addr", "CW_Angle_Limit", value_of_max_radian_position) && sendCommandMsg("addr", "CCW_Angle_Limit", value_of_max_radian_position))
126  return true;
127  else
128  return false;
129  }
130  }
131  else
132  {
133  if (model_name.find("MX") != std::string::npos)
134  {
135  if (model_name.find("MX-28-2") != std::string::npos)
136  {
137  if (index == "velocity_control")
138  {
139  if (sendCommandMsg("addr", "Operating_Mode", 1))
140  return true;
141  else
142  return false;
143  }
144  else if (index == "position_control")
145  {
146  if (sendCommandMsg("addr", "Operating_Mode", 3))
147  return true;
148  else
149  return false;
150  }
151  else if (index == "extended_position_control")
152  {
153  if (sendCommandMsg("addr", "Operating_Mode", 4))
154  return true;
155  else
156  return false;
157  }
158  else if (index == "pwm_control")
159  {
160  if (sendCommandMsg("addr", "Operating_Mode", 16))
161  return true;
162  else
163  return false;
164  }
165  }
166  else if (model_name.find("MX-64-2") != std::string::npos ||
167  model_name.find("MX-106-2") != std::string::npos )
168  {
169  if (index == "current_control")
170  {
171  if (sendCommandMsg("addr", "Operating_Mode", 0))
172  return true;
173  else
174  return false;
175  }
176  else if (index == "velocity_control")
177  {
178  if (sendCommandMsg("addr", "Operating_Mode", 1))
179  return true;
180  else
181  return false;
182  }
183  else if (index == "position_control")
184  {
185  if (sendCommandMsg("addr", "Operating_Mode", 3))
186  return true;
187  else
188  return false;
189  }
190  else if (index == "extended_position_control")
191  {
192  if (sendCommandMsg("addr", "Operating_Mode", 4))
193  return true;
194  else
195  return false;
196  }
197  else if (index == "current_based_position_control")
198  {
199  if (sendCommandMsg("addr", "Operating_Mode", 5))
200  return true;
201  else
202  return false;
203  }
204  else if (index == "pwm_control")
205  {
206  if (sendCommandMsg("addr", "Operating_Mode", 16))
207  return true;
208  else
209  return false;
210  }
211  }
212  }
213  if (model_name.find("XL") != std::string::npos)
214  {
215  if (model_name.find("XL-320") != std::string::npos)
216  {
217  if (index == "position_control")
218  {
219  if (sendCommandMsg("addr", "CW_Angle_Limit", 0) && sendCommandMsg("addr", "CCW_Angle_Limit", value_of_max_radian_position))
220  return true;
221  else
222  return false;
223  }
224  else if (index == "velocity_control")
225  {
226  if (sendCommandMsg("addr", "CW_Angle_Limit", 0) && sendCommandMsg("addr", "CCW_Angle_Limit", 0))
227  return true;
228  else
229  return false;
230  }
231  }
232  else if (model_name.find("XL430-W250") != std::string::npos)
233  {
234  if (index == "velocity_control")
235  {
236  if (sendCommandMsg("addr", "Operating_Mode", 1))
237  return true;
238  else
239  return false;
240  }
241  else if (index == "position_control")
242  {
243  if (sendCommandMsg("addr", "Operating_Mode", 3))
244  return true;
245  else
246  return false;
247  }
248  else if (index == "extended_position_control")
249  {
250  if (sendCommandMsg("addr", "Operating_Mode", 4))
251  return true;
252  else
253  return false;
254  }
255  else if (index == "pwm_control")
256  {
257  if (sendCommandMsg("addr", "Operating_Mode", 16))
258  return true;
259  else
260  return false;
261  }
262  }
263  }
264  if (model_name.find("XM") != std::string::npos ||
265  model_name.find("XH") != std::string::npos )
266  {
267  if (index == "current_control")
268  {
269  if (sendCommandMsg("addr", "Operating_Mode", 0))
270  return true;
271  else
272  return false;
273  }
274  else if (index == "velocity_control")
275  {
276  if (sendCommandMsg("addr", "Operating_Mode", 1))
277  return true;
278  else
279  return false;
280  }
281  else if (index == "position_control")
282  {
283  if (sendCommandMsg("addr", "Operating_Mode", 3))
284  return true;
285  else
286  return false;
287  }
288  else if (index == "extended_position_control")
289  {
290  if (sendCommandMsg("addr", "Operating_Mode", 4))
291  return true;
292  else
293  return false;
294  }
295  else if (index == "current_based_position_control")
296  {
297  if (sendCommandMsg("addr", "Operating_Mode", 5))
298  return true;
299  else
300  return false;
301  }
302  else if (index == "pwm_control")
303  {
304  if (sendCommandMsg("addr", "Operating_Mode", 16))
305  return true;
306  else
307  return false;
308  }
309  }
310  else if (model_name.find("PRO") != std::string::npos)
311  {
312  if (index == "torque_control")
313  {
314  if (sendCommandMsg("addr", "Operating_Mode", 0))
315  return true;
316  else
317  return false;
318  }
319  else if (index == "velocity_control")
320  {
321  if (sendCommandMsg("addr", "Operating_Mode", 1))
322  return true;
323  else
324  return false;
325  }
326  else if (index == "position_control")
327  {
328  if (sendCommandMsg("addr", "Operating_Mode", 3))
329  return true;
330  else
331  return false;
332  }
333  else if (index == "extended_position_control")
334  {
335  if (sendCommandMsg("addr", "Operating_Mode", 4))
336  return true;
337  else
338  return false;
339  }
340  }
341  }
342 }
343 
344 bool QNode::sendTorqueMsg(int64_t onoff)
345 {
346  if (sendCommandMsg("addr", "Torque_Enable", onoff))
347  return true;
348  else
349  return false;
350 }
351 
353 {
354  if (sendCommandMsg("reboot"))
355  return true;
356  else
357  return false;
358 }
359 
361 {
362  if (sendCommandMsg("factory_reset"))
363  {
365  return true;
366  }
367  else
368  {
369  return false;
370  }
371 }
372 
373 bool QNode::setPositionZeroMsg(int32_t zero_position)
374 {
375  if (sendCommandMsg("addr", "Goal_Position", zero_position))
376  return true;
377  else
378  return false;
379 }
380 
381 bool QNode::sendAddressValueMsg(std::string addr_name, int64_t value)
382 {
383  if (sendCommandMsg("addr", addr_name, value))
384  return true;
385  else
386  return false;
387 }
388 
390 {
391  dynamixel_workbench_msgs::GetDynamixelInfo get_dynamixel_info;
392 
393  if (dynamixel_info_client_.call(get_dynamixel_info))
394  {
395  dynamixel_info_.load_info.device_name = get_dynamixel_info.response.dynamixel_info.load_info.device_name;
396  dynamixel_info_.load_info.baud_rate = get_dynamixel_info.response.dynamixel_info.load_info.baud_rate;
397  dynamixel_info_.load_info.protocol_version = get_dynamixel_info.response.dynamixel_info.load_info.protocol_version;
398 
399  dynamixel_info_.model_id = get_dynamixel_info.response.dynamixel_info.model_id;
400  dynamixel_info_.model_name = get_dynamixel_info.response.dynamixel_info.model_name;
401  dynamixel_info_.model_number = get_dynamixel_info.response.dynamixel_info.model_number;
402 
404  }
405 }
406 
408 {
409  ros::NodeHandle node_handle;
410 
411  if (dynamixel_info_.model_name.find("AX") != std::string::npos)
412  {
413  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("AX"), 10, &QNode::AXStatusMsgCallback, this);
415  }
416  else if (dynamixel_info_.model_name.find("RX") != std::string::npos)
417  {
418  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("RX"), 10, &QNode::RXStatusMsgCallback, this);
420  }
421  else if (dynamixel_info_.model_name.find("MX") != std::string::npos)
422  {
423  if (dynamixel_info_.model_name.find("MX-28-2") != std::string::npos)
424  {
425  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("MX"), 10, &QNode::MX2StatusMsgCallback, this);
427  }
428  else if (dynamixel_info_.model_name.find("MX-64-2") != std::string::npos ||
429  dynamixel_info_.model_name.find("MX-106-2") != std::string::npos)
430  {
431  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("MX"), 10, &QNode::MX2ExtStatusMsgCallback, this);
433  }
434  else if (dynamixel_info_.model_name.find("MX-12W") != std::string::npos ||
435  dynamixel_info_.model_name.find("MX-28") != std::string::npos)
436  {
437  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("MX"), 10, &QNode::MXStatusMsgCallback, this);
439  }
440  else if (dynamixel_info_.model_name.find("MX-64") != std::string::npos ||
441  dynamixel_info_.model_name.find("MX-106") != std::string::npos)
442  {
443  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("MX"), 10, &QNode::MXExtStatusMsgCallback, this);
445  }
446  }
447  else if (dynamixel_info_.model_name.find("EX") != std::string::npos)
448  {
449  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("EX"), 10, &QNode::EXStatusMsgCallback, this);
451  }
452  else if (dynamixel_info_.model_name.find("XL") != std::string::npos)
453  {
454  if (dynamixel_info_.model_name.find("XL-320") != std::string::npos)
455  {
456  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("XL"), 10, &QNode::XL320StatusMsgCallback, this);
458  }
459  else if (dynamixel_info_.model_name.find("XL430-W250") != std::string::npos)
460  {
461  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("XL"), 10, &QNode::XLStatusMsgCallback, this);
463  }
464  }
465  else if (dynamixel_info_.model_name.find("XM") != std::string::npos)
466  {
467  if (dynamixel_info_.model_name.find("XM430-W210") != std::string::npos ||
468  dynamixel_info_.model_name.find("XM430-W350") != std::string::npos)
469  {
470  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("XM"), 10, &QNode::XMStatusMsgCallback, this);
472  }
473  else if (dynamixel_info_.model_name.find("XM540-W150") != std::string::npos ||
474  dynamixel_info_.model_name.find("XM540-W270") != std::string::npos)
475  {
476  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("XM"), 10, &QNode::XMExtStatusMsgCallback, this);
478  }
479  }
480  else if (dynamixel_info_.model_name.find("XH") != std::string::npos)
481  {
482  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("XH"), 10, &QNode::XHStatusMsgCallback, this);
484  }
485  else if (dynamixel_info_.model_name.find("PRO") != std::string::npos)
486  {
487  if (dynamixel_info_.model_name.find("PRO_L42_10_S300_R") != std::string::npos)
488  {
489  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("PRO"), 10, &QNode::PROStatusMsgCallback, this);
491  }
492  else
493  {
494  dynamixel_status_msg_sub_ = node_handle.subscribe("dynamixel/" + std::string("PRO"), 10, &QNode::PROExtStatusMsgCallback, this);
496  }
497  }
498 }
499 
501 {
502  ros::Rate loop_rate(1000);
503 
504  while (ros::ok())
505  {
506  ros::spinOnce();
507  loop_rate.sleep();
508  }
509 
510  std::cout << "ROS shutdown, proceeding to close the gui." << std::endl;
511  Q_EMIT rosShutdown();
512 }
513 
514 void QNode::log(const std::string &msg, int64_t sender)
515 {
516  if(logging_model_.rowCount() == row_count_)
517  logging_model_.insertRows(row_count_, 1);
518 
519  std::stringstream logging_model_msg;
520 
521  logging_model_msg << msg << sender;
522 
523  QVariant new_row(QString(logging_model_msg.str().c_str()));
524  logging_model_.setData(logging_model_.index(row_count_), new_row);
525 
526  row_count_++;
527 }
528 
529 void QNode::log(const std::string &msg)
530 {
531  if(logging_model_.rowCount() == row_count_)
532  logging_model_.insertRows(row_count_, 1);
533 
534  std::stringstream logging_model_msg;
535 
536  logging_model_msg << msg;
537 
538  QVariant new_row(QString(logging_model_msg.str().c_str()));
539  logging_model_.setData(logging_model_.index(row_count_), new_row);
540 
541  row_count_++;
542 }
543 
545 {
546  pthread_mutex_lock(&mutex);
547  (this->*dynamixelDataLogPtr)();
548  pthread_mutex_unlock(&mutex);
549  row_count_ = 0;
550 }
551 
552 void QNode::AX()
553 {
554  log(std::string("< EEPROM >"));
555  log(std::string("Model_Number: "), ax_msgs_.Model_Number);
556  log(std::string("Firmware_Version: "), ax_msgs_.Firmware_Version);
557  log(std::string("ID: "), ax_msgs_.ID);
558  log(std::string("Baud_Rate: "), ax_msgs_.Baud_Rate);
559  log(std::string("Return_Delay_Time: "), ax_msgs_.Return_Delay_Time);
560  log(std::string("CW_Angle_Limit: "), ax_msgs_.CW_Angle_Limit);
561  log(std::string("CCW_Angle_Limit: "), ax_msgs_.CCW_Angle_Limit);
562  log(std::string("Temperature_Limit: "), ax_msgs_.Temperature_Limit);
563  log(std::string("Min_Voltage_Limit: "), ax_msgs_.Min_Voltage_Limit);
564  log(std::string("Max_Voltage_Limit: "), ax_msgs_.Max_Voltage_Limit);
565  log(std::string("Max_Torque: "), ax_msgs_.Max_Torque);
566  log(std::string("Status_Return_Level: "), ax_msgs_.Status_Return_Level);
567  log(std::string("Alarm_LED: "), ax_msgs_.Alarm_LED);
568  log(std::string("Shutdown: "), ax_msgs_.Shutdown);
569  log(std::string(""));
570  log(std::string("< RAM >"));
571  log(std::string("Torque_Enable: "), ax_msgs_.Torque_Enable);
572  log(std::string("LED: "), ax_msgs_.LED);
573  log(std::string("CW_Compliance_Margin: "), ax_msgs_.CW_Compliance_Margin);
574  log(std::string("CCW_Compliance_Margin: "), ax_msgs_.CCW_Compliance_Margin);
575  log(std::string("CW_Compliance_Slope: "), ax_msgs_.CW_Compliance_Slope);
576  log(std::string("CCW_Compliance_Slope: "), ax_msgs_.CCW_Compliance_Slope);
577  log(std::string("Goal_Position: "), ax_msgs_.Goal_Position);
578  log(std::string("Moving_Speed: "), ax_msgs_.Moving_Speed);
579  log(std::string("Torque_Limit: "), ax_msgs_.Torque_Limit);
580  log(std::string("Present_Position: "), ax_msgs_.Present_Position);
581  log(std::string("Present_Speed: "), ax_msgs_.Present_Speed);
582  log(std::string("Present_Load: "), ax_msgs_.Present_Load);
583  log(std::string("Present_Voltage: "), ax_msgs_.Present_Voltage);
584  log(std::string("Present_Temperature: "), ax_msgs_.Present_Temperature);
585  log(std::string("Registered: "), ax_msgs_.Registered);
586  log(std::string("Moving: "), ax_msgs_.Moving);
587  log(std::string("Lock: "), ax_msgs_.Lock);
588  log(std::string("Punch: "), ax_msgs_.Punch);
589 }
590 
591 void QNode::RX()
592 {
593  log(std::string("< EEPROM >"));
594  log(std::string("Model_Number: "), rx_msgs_.Model_Number);
595  log(std::string("Firmware_Version: "), rx_msgs_.Firmware_Version);
596  log(std::string("ID: "), rx_msgs_.ID);
597  log(std::string("Baud_Rate: "), rx_msgs_.Baud_Rate);
598  log(std::string("Return_Delay_Time: "), rx_msgs_.Return_Delay_Time);
599  log(std::string("CW_Angle_Limit: "), rx_msgs_.CW_Angle_Limit);
600  log(std::string("CCW_Angle_Limit: "), rx_msgs_.CCW_Angle_Limit);
601  log(std::string("Temperature_Limit: "), rx_msgs_.Temperature_Limit);
602  log(std::string("Min_Voltage_Limit: "), rx_msgs_.Min_Voltage_Limit);
603  log(std::string("Max_Voltage_Limit: "), rx_msgs_.Max_Voltage_Limit);
604  log(std::string("Max_Torque: "), rx_msgs_.Max_Torque);
605  log(std::string("Status_Return_Level: "), rx_msgs_.Status_Return_Level);
606  log(std::string("Alarm_LED: "), rx_msgs_.Alarm_LED);
607  log(std::string("Shutdown: "), rx_msgs_.Shutdown);
608  log(std::string(""));
609  log(std::string("< RAM >"));
610  log(std::string("Torque_Enable: "), rx_msgs_.Torque_Enable);
611  log(std::string("LED: "), rx_msgs_.LED);
612  log(std::string("CW_Compliance_Margin: "), rx_msgs_.CW_Compliance_Margin);
613  log(std::string("CCW_Compliance_Margin: "), rx_msgs_.CCW_Compliance_Margin);
614  log(std::string("CW_Compliance_Slope: "), rx_msgs_.CW_Compliance_Slope);
615  log(std::string("CCW_Compliance_Slope: "), rx_msgs_.CCW_Compliance_Slope);
616  log(std::string("Goal_Position: "), rx_msgs_.Goal_Position);
617  log(std::string("Moving_Speed: "), rx_msgs_.Moving_Speed);
618  log(std::string("Torque_Limit: "), rx_msgs_.Torque_Limit);
619  log(std::string("Present_Position: "), rx_msgs_.Present_Position);
620  log(std::string("Present_Speed: "), rx_msgs_.Present_Speed);
621  log(std::string("Present_Load: "), rx_msgs_.Present_Load);
622  log(std::string("Present_Voltage: "), rx_msgs_.Present_Voltage);
623  log(std::string("Present_Temperature: "), rx_msgs_.Present_Temperature);
624  log(std::string("Registered: "), rx_msgs_.Registered);
625  log(std::string("Moving: "), rx_msgs_.Moving);
626  log(std::string("Lock: "), rx_msgs_.Lock);
627  log(std::string("Punch: "), rx_msgs_.Punch);
628 }
629 
630 void QNode::MX()
631 {
632  log(std::string("< EEPROM >"));
633  log(std::string("Model_Number: "), mx_msgs_.Model_Number);
634  log(std::string("Firmware_Version: "), mx_msgs_.Firmware_Version);
635  log(std::string("ID: "), mx_msgs_.ID);
636  log(std::string("Baud_Rate: "), mx_msgs_.Baud_Rate);
637  log(std::string("Return_Delay_Time: "), mx_msgs_.Return_Delay_Time);
638  log(std::string("CW_Angle_Limit: "), mx_msgs_.CW_Angle_Limit);
639  log(std::string("CCW_Angle_Limit: "), mx_msgs_.CCW_Angle_Limit);
640  log(std::string("Temperature_Limit: "), mx_msgs_.Temperature_Limit);
641  log(std::string("Min_Voltage_Limit: "), mx_msgs_.Min_Voltage_Limit);
642  log(std::string("Max_Voltage_Limit: "), mx_msgs_.Max_Voltage_Limit);
643  log(std::string("Max_Torque: "), mx_msgs_.Max_Torque);
644  log(std::string("Status_Return_Level: "), mx_msgs_.Status_Return_Level);
645  log(std::string("Alarm_LED: "), mx_msgs_.Alarm_LED);
646  log(std::string("Shutdown: "), mx_msgs_.Shutdown);
647  log(std::string("Multi_Turn_Offset: "), mx_msgs_.Multi_Turn_Offset);
648  log(std::string("Resolution_Divider: "), mx_msgs_.Resolution_Divider);
649  log(std::string(""));
650  log(std::string("< RAM >"));
651  log(std::string("Torque_Enable: "), mx_msgs_.Torque_Enable);
652  log(std::string("LED: "), mx_msgs_.LED);
653  log(std::string("D_gain: "), mx_msgs_.D_gain);
654  log(std::string("I_gain: "), mx_msgs_.I_gain);
655  log(std::string("P_gain: "), mx_msgs_.P_gain);
656  log(std::string("Goal_Position: "), mx_msgs_.Goal_Position);
657  log(std::string("Moving_Speed: "), mx_msgs_.Moving_Speed);
658  log(std::string("Torque_Limit: "), mx_msgs_.Torque_Limit);
659  log(std::string("Present_Position: "), mx_msgs_.Present_Position);
660  log(std::string("Present_Speed: "), mx_msgs_.Present_Speed);
661  log(std::string("Present_Load: "), mx_msgs_.Present_Load);
662  log(std::string("Present_Voltage: "), mx_msgs_.Present_Voltage);
663  log(std::string("Present_Temperature: "), mx_msgs_.Present_Temperature);
664  log(std::string("Registered: "), mx_msgs_.Registered);
665  log(std::string("Moving: "), mx_msgs_.Moving);
666  log(std::string("Lock: "), mx_msgs_.Lock);
667  log(std::string("Punch: "), mx_msgs_.Punch);
668  log(std::string("Goal_Acceleration: "), mx_msgs_.Goal_Acceleration);
669 }
670 
672 {
673  log(std::string("< EEPROM >"));
674  log(std::string("Model_Number: "), mxext_msgs_.Model_Number);
675  log(std::string("Firmware_Version: "), mxext_msgs_.Firmware_Version);
676  log(std::string("ID: "), mxext_msgs_.ID);
677  log(std::string("Baud_Rate: "), mxext_msgs_.Baud_Rate);
678  log(std::string("Return_Delay_Time: "), mxext_msgs_.Return_Delay_Time);
679  log(std::string("CW_Angle_Limit: "), mxext_msgs_.CW_Angle_Limit);
680  log(std::string("CCW_Angle_Limit: "), mxext_msgs_.CCW_Angle_Limit);
681  log(std::string("Temperature_Limit: "), mxext_msgs_.Temperature_Limit);
682  log(std::string("Min_Voltage_Limit: "), mxext_msgs_.Min_Voltage_Limit);
683  log(std::string("Max_Voltage_Limit: "), mxext_msgs_.Max_Voltage_Limit);
684  log(std::string("Max_Torque: "), mxext_msgs_.Max_Torque);
685  log(std::string("Status_Return_Level: "), mxext_msgs_.Status_Return_Level);
686  log(std::string("Alarm_LED: "), mxext_msgs_.Alarm_LED);
687  log(std::string("Shutdown: "), mxext_msgs_.Shutdown);
688  log(std::string("Multi_Turn_Offset: "), mxext_msgs_.Multi_Turn_Offset);
689  log(std::string("Resolution_Divider: "), mxext_msgs_.Resolution_Divider);
690  log(std::string(""));
691  log(std::string("< RAM >"));
692  log(std::string("Torque_Enable: "), mxext_msgs_.Torque_Enable);
693  log(std::string("LED: "), mxext_msgs_.LED);
694  log(std::string("D_gain: "), mxext_msgs_.D_gain);
695  log(std::string("I_gain: "), mxext_msgs_.I_gain);
696  log(std::string("P_gain: "), mxext_msgs_.P_gain);
697  log(std::string("Goal_Position: "), mxext_msgs_.Goal_Position);
698  log(std::string("Moving_Speed: "), mxext_msgs_.Moving_Speed);
699  log(std::string("Torque_Limit: "), mxext_msgs_.Torque_Limit);
700  log(std::string("Present_Position: "), mxext_msgs_.Present_Position);
701  log(std::string("Present_Speed: "), mxext_msgs_.Present_Speed);
702  log(std::string("Present_Load: "), mxext_msgs_.Present_Load);
703  log(std::string("Present_Voltage: "), mxext_msgs_.Present_Voltage);
704  log(std::string("Present_Temperature: "), mxext_msgs_.Present_Temperature);
705  log(std::string("Registered: "), mxext_msgs_.Registered);
706  log(std::string("Moving: "), mxext_msgs_.Moving);
707  log(std::string("Lock: "), mxext_msgs_.Lock);
708  log(std::string("Punch: "), mxext_msgs_.Punch);
709  log(std::string("Current: "), mxext_msgs_.Current);
710  log(std::string("Torque_Control_Mode_Enable: "), mxext_msgs_.Torque_Control_Mode_Enable);
711  log(std::string("Goal_Torque: "), mxext_msgs_.Goal_Torque);
712  log(std::string("Goal_Acceleration: "), mxext_msgs_.Goal_Acceleration);
713 }
714 
716 {
717  log(std::string("< EEPROM >"));
718  log(std::string("Model_Number: "), mx2_msgs_.Model_Number);
719  log(std::string("Firmware_Version: "), mx2_msgs_.Firmware_Version);
720  log(std::string("ID: "), mx2_msgs_.ID);
721  log(std::string("Baud_Rate: "), mx2_msgs_.Baud_Rate);
722  log(std::string("Return_Delay_Time: "), mx2_msgs_.Return_Delay_Time);
723  log(std::string("Drive_Mode: "), mx2_msgs_.Drive_Mode);
724  log(std::string("Operating_Mode: "), mx2_msgs_.Operating_Mode);
725  log(std::string("Secondary_ID: "), mx2_msgs_.Secondary_ID);
726  log(std::string("Protocol_Version: "), mx2_msgs_.Protocol_Version);
727  log(std::string("Homing_Offset: "), mx2_msgs_.Homing_Offset);
728  log(std::string("Moving_Threshold: "), mx2_msgs_.Moving_Threshold);
729  log(std::string("Temperature_Limit: "), mx2_msgs_.Temperature_Limit);
730  log(std::string("Max_Voltage_Limit: "), mx2_msgs_.Max_Voltage_Limit);
731  log(std::string("Min_Voltage_Limit: "), mx2_msgs_.Min_Voltage_Limit);
732  log(std::string("PWM_Limit: "), mx2_msgs_.PWM_Limit);
733  log(std::string("Acceleration_Limit: "), mx2_msgs_.Acceleration_Limit);
734  log(std::string("Velocity_Limit: "), mx2_msgs_.Velocity_Limit);
735  log(std::string("Max_Position_Limit: "), mx2_msgs_.Max_Position_Limit);
736  log(std::string("Min_Position_Limit: "), mx2_msgs_.Min_Position_Limit);
737  log(std::string("Shutdown: "), mx2_msgs_.Shutdown);
738  log(std::string(""));
739  log(std::string("< RAM >"));
740  log(std::string("Torque_Enable: "), mx2_msgs_.Torque_Enable);
741  log(std::string("LED: "), mx2_msgs_.LED);
742  log(std::string("Status_Return_Level: "), mx2_msgs_.Status_Return_Level);
743  log(std::string("Registered_Instruction: "), mx2_msgs_.Registered_Instruction);
744  log(std::string("Hardware_Error_Status: "), mx2_msgs_.Hardware_Error_Status);
745  log(std::string("Velocity_I_Gain: "), mx2_msgs_.Velocity_I_Gain);
746  log(std::string("Velocity_P_Gain: "), mx2_msgs_.Velocity_P_Gain);
747  log(std::string("Position_D_Gain: "), mx2_msgs_.Position_D_Gain);
748  log(std::string("Position_I_Gain: "), mx2_msgs_.Position_I_Gain);
749  log(std::string("Position_P_Gain: "), mx2_msgs_.Position_P_Gain);
750  log(std::string("Feedforward_2nd_Gain: "), mx2_msgs_.Feedforward_2nd_Gain);
751  log(std::string("Feedforward_1st_Gain: "), mx2_msgs_.Feedforward_1st_Gain);
752  log(std::string("Bus_Watchdog: "), mx2_msgs_.Bus_Watchdog);
753  log(std::string("Goal_PWM: "), mx2_msgs_.Goal_PWM);
754  log(std::string("Goal_Velocity: "), mx2_msgs_.Goal_Velocity);
755  log(std::string("Profile_Acceleration: "), mx2_msgs_.Profile_Acceleration);
756  log(std::string("Profile_Velocity: "), mx2_msgs_.Profile_Velocity);
757  log(std::string("Goal_Position: "), mx2_msgs_.Goal_Position);
758  log(std::string("Realtime_Tick: "), mx2_msgs_.Realtime_Tick);
759  log(std::string("Moving: "), mx2_msgs_.Moving);
760  log(std::string("Moving_Status: "), mx2_msgs_.Moving_Status);
761  log(std::string("Present_PWM: "), mx2_msgs_.Present_PWM);
762  log(std::string("Present_Load: "), mx2_msgs_.Present_Load);
763  log(std::string("Present_Velocity: "), mx2_msgs_.Present_Velocity);
764  log(std::string("Present_Position: "), mx2_msgs_.Present_Position);
765  log(std::string("Velocity_Trajectory: "), mx2_msgs_.Velocity_Trajectory);
766  log(std::string("Position_Trajectory: "), mx2_msgs_.Position_Trajectory);
767  log(std::string("Present_Input_Voltage: "), mx2_msgs_.Present_Input_Voltage);
768  log(std::string("Present_Temperature: "), mx2_msgs_.Present_Temperature);
769 }
770 
772 {
773  log(std::string("< EEPROM >"));
774  log(std::string("Model_Number: "), mx2ext_msgs_.Model_Number);
775  log(std::string("Firmware_Version: "), mx2ext_msgs_.Firmware_Version);
776  log(std::string("ID: "), mx2ext_msgs_.ID);
777  log(std::string("Baud_Rate: "), mx2ext_msgs_.Baud_Rate);
778  log(std::string("Return_Delay_Time: "), mx2ext_msgs_.Return_Delay_Time);
779  log(std::string("Drive_Mode: "), mx2ext_msgs_.Drive_Mode);
780  log(std::string("Operating_Mode: "), mx2ext_msgs_.Operating_Mode);
781  log(std::string("Secondary_ID: "), mx2ext_msgs_.Secondary_ID);
782  log(std::string("Protocol_Version: "), mx2ext_msgs_.Protocol_Version);
783  log(std::string("Homing_Offset: "), mx2ext_msgs_.Homing_Offset);
784  log(std::string("Moving_Threshold: "), mx2ext_msgs_.Moving_Threshold);
785  log(std::string("Temperature_Limit: "), mx2ext_msgs_.Temperature_Limit);
786  log(std::string("Max_Voltage_Limit: "), mx2ext_msgs_.Max_Voltage_Limit);
787  log(std::string("Min_Voltage_Limit: "), mx2ext_msgs_.Min_Voltage_Limit);
788  log(std::string("PWM_Limit: "), mx2ext_msgs_.PWM_Limit);
789  log(std::string("Current_Limit: "), mx2ext_msgs_.Current_Limit);
790  log(std::string("Acceleration_Limit: "), mx2ext_msgs_.Acceleration_Limit);
791  log(std::string("Velocity_Limit: "), mx2ext_msgs_.Velocity_Limit);
792  log(std::string("Max_Position_Limit: "), mx2ext_msgs_.Max_Position_Limit);
793  log(std::string("Min_Position_Limit: "), mx2ext_msgs_.Min_Position_Limit);
794  log(std::string("Shutdown: "), mx2ext_msgs_.Shutdown);
795  log(std::string(""));
796  log(std::string("< RAM >"));
797  log(std::string("Torque_Enable: "), mx2ext_msgs_.Torque_Enable);
798  log(std::string("LED: "), mx2ext_msgs_.LED);
799  log(std::string("Status_Return_Level: "), mx2ext_msgs_.Status_Return_Level);
800  log(std::string("Registered_Instruction: "), mx2ext_msgs_.Registered_Instruction);
801  log(std::string("Hardware_Error_Status: "), mx2ext_msgs_.Hardware_Error_Status);
802  log(std::string("Velocity_I_Gain: "), mx2ext_msgs_.Velocity_I_Gain);
803  log(std::string("Velocity_P_Gain: "), mx2ext_msgs_.Velocity_P_Gain);
804  log(std::string("Position_D_Gain: "), mx2ext_msgs_.Position_D_Gain);
805  log(std::string("Position_I_Gain: "), mx2ext_msgs_.Position_I_Gain);
806  log(std::string("Position_P_Gain: "), mx2ext_msgs_.Position_P_Gain);
807  log(std::string("Feedforward_2nd_Gain: "), mx2ext_msgs_.Feedforward_2nd_Gain);
808  log(std::string("Feedforward_1st_Gain: "), mx2ext_msgs_.Feedforward_1st_Gain);
809  log(std::string("Bus_Watchdog: "), mx2ext_msgs_.Bus_Watchdog);
810  log(std::string("Goal_PWM: "), mx2ext_msgs_.Goal_PWM);
811  log(std::string("Goal_Velocity: "), mx2ext_msgs_.Goal_Velocity);
812  log(std::string("Profile_Acceleration: "), mx2ext_msgs_.Profile_Acceleration);
813  log(std::string("Profile_Velocity: "), mx2ext_msgs_.Profile_Velocity);
814  log(std::string("Goal_Position: "), mx2ext_msgs_.Goal_Position);
815  log(std::string("Realtime_Tick: "), mx2ext_msgs_.Realtime_Tick);
816  log(std::string("Moving: "), mx2ext_msgs_.Moving);
817  log(std::string("Moving_Status: "), mx2ext_msgs_.Moving_Status);
818  log(std::string("Present_PWM: "), mx2ext_msgs_.Present_PWM);
819  log(std::string("Present_Current: "), mx2ext_msgs_.Present_Current);
820  log(std::string("Present_Velocity: "), mx2ext_msgs_.Present_Velocity);
821  log(std::string("Present_Position: "), mx2ext_msgs_.Present_Position);
822  log(std::string("Velocity_Trajectory: "), mx2ext_msgs_.Velocity_Trajectory);
823  log(std::string("Position_Trajectory: "), mx2ext_msgs_.Position_Trajectory);
824  log(std::string("Present_Input_Voltage: "), mx2ext_msgs_.Present_Input_Voltage);
825  log(std::string("Present_Temperature: "), mx2ext_msgs_.Present_Temperature);
826 }
827 
828 void QNode::EX()
829 {
830  log(std::string("< EEPROM >"));
831  log(std::string("Model_Number: "), ex_msgs_.Model_Number);
832  log(std::string("Firmware_Version: "), ex_msgs_.Firmware_Version);
833  log(std::string("ID: "), ex_msgs_.ID);
834  log(std::string("Baud_Rate: "), ex_msgs_.Baud_Rate);
835  log(std::string("Return_Delay_Time: "), ex_msgs_.Return_Delay_Time);
836  log(std::string("CW_Angle_Limit: "), ex_msgs_.CW_Angle_Limit);
837  log(std::string("CCW_Angle_Limit: "), ex_msgs_.CCW_Angle_Limit);
838  log(std::string("Drive_Mode: "), ex_msgs_.Drive_Mode);
839  log(std::string("Temperature_Limit: "), ex_msgs_.Temperature_Limit);
840  log(std::string("Min_Voltage_Limit: "), ex_msgs_.Min_Voltage_Limit);
841  log(std::string("Max_Voltage_Limit: "), ex_msgs_.Max_Voltage_Limit);
842  log(std::string("Max_Torque: "), ex_msgs_.Max_Torque);
843  log(std::string("Status_Return_Level: "), ex_msgs_.Status_Return_Level);
844  log(std::string("Alarm_LED: "), ex_msgs_.Alarm_LED);
845  log(std::string("Shutdown: "), ex_msgs_.Shutdown);
846  log(std::string(""));
847  log(std::string("< RAM >"));
848  log(std::string("Torque_Enable: "), ex_msgs_.Torque_Enable);
849  log(std::string("LED: "), ex_msgs_.LED);
850  log(std::string("CW_Compliance_Margin: "), ex_msgs_.CW_Compliance_Margin);
851  log(std::string("CCW_Compliance_Margin: "), ex_msgs_.CCW_Compliance_Margin);
852  log(std::string("CW_Compliance_Slope: "), ex_msgs_.CW_Compliance_Slope);
853  log(std::string("CCW_Compliance_Slope: "), ex_msgs_.CCW_Compliance_Slope);
854  log(std::string("Goal_Position: "), ex_msgs_.Goal_Position);
855  log(std::string("Moving_Speed: "), ex_msgs_.Moving_Speed);
856  log(std::string("Torque_Limit: "), ex_msgs_.Torque_Limit);
857  log(std::string("Present_Position: "), ex_msgs_.Present_Position);
858  log(std::string("Present_Speed: "), ex_msgs_.Present_Speed);
859  log(std::string("Present_Load: "), ex_msgs_.Present_Load);
860  log(std::string("Present_Voltage: "), ex_msgs_.Present_Voltage);
861  log(std::string("Present_Temperature: "), ex_msgs_.Present_Temperature);
862  log(std::string("Registered: "), ex_msgs_.Registered);
863  log(std::string("Moving: "), ex_msgs_.Moving);
864  log(std::string("Lock: "), ex_msgs_.Lock);
865  log(std::string("Punch: "), ex_msgs_.Punch);
866  log(std::string("Sensored_Current: "), ex_msgs_.Sensored_Current);
867 }
868 
870 {
871  log(std::string("< EEPROM >"));
872  log(std::string("Model_Number: "), xl320_msgs_.Model_Number);
873  log(std::string("Firmware_Version: "), xl320_msgs_.Firmware_Version);
874  log(std::string("ID: "), xl320_msgs_.ID);
875  log(std::string("Baud_Rate: "), xl320_msgs_.Baud_Rate);
876  log(std::string("Return_Delay_Time: "), xl320_msgs_.Return_Delay_Time);
877  log(std::string("CW_Angle_Limit: "), xl320_msgs_.CW_Angle_Limit);
878  log(std::string("CCW_Angle_Limit: "), xl320_msgs_.CCW_Angle_Limit);
879  log(std::string("Control_Mode: "), xl320_msgs_.Control_Mode);
880  log(std::string("Temperature_Limit: "), xl320_msgs_.Temperature_Limit);
881  log(std::string("Min_Voltage_Limit: "), xl320_msgs_.Min_Voltage_Limit);
882  log(std::string("Max_Voltage_Limit: "), xl320_msgs_.Max_Voltage_Limit);
883  log(std::string("Max_Torque: "), xl320_msgs_.Max_Torque);
884  log(std::string("Status_Return_Level: "), xl320_msgs_.Status_Return_Level);
885  log(std::string("Shutdown: "), xl320_msgs_.Shutdown);
886  log(std::string(""));
887  log(std::string("< RAM >"));
888  log(std::string("Torque_Enable: "), xl320_msgs_.Torque_Enable);
889  log(std::string("LED: "), xl320_msgs_.LED);
890  log(std::string("D_gain: "), xl320_msgs_.D_gain);
891  log(std::string("I_gain: "), xl320_msgs_.I_gain);
892  log(std::string("P_gain: "), xl320_msgs_.P_gain);
893  log(std::string("Goal_Position: "), xl320_msgs_.Goal_Position);
894  log(std::string("Moving_Speed: "), xl320_msgs_.Moving_Speed);
895  log(std::string("Torque_Limit: "), xl320_msgs_.Torque_Limit);
896  log(std::string("Present_Position: "), xl320_msgs_.Present_Position);
897  log(std::string("Present_Speed: "), xl320_msgs_.Present_Speed);
898  log(std::string("Present_Load: "), xl320_msgs_.Present_Load);
899  log(std::string("Present_Voltage: "), xl320_msgs_.Present_Voltage);
900  log(std::string("Present_Temperature: "), xl320_msgs_.Present_Temperature);
901  log(std::string("Registered: "), xl320_msgs_.Registered);
902  log(std::string("Moving: "), xl320_msgs_.Moving);
903  log(std::string("Hardware_Error_Status: "), xl320_msgs_.Hardware_Error_Status);
904  log(std::string("Punch: "), xl320_msgs_.Punch);
905 }
906 
907 void QNode::XL()
908 {
909  log(std::string("< EEPROM >"));
910  log(std::string("Model_Number: "), xl_msgs_.Model_Number);
911  log(std::string("Firmware_Version: "), xl_msgs_.Firmware_Version);
912  log(std::string("ID: "), xl_msgs_.ID);
913  log(std::string("Baud_Rate: "), xl_msgs_.Baud_Rate);
914  log(std::string("Return_Delay_Time: "), xl_msgs_.Return_Delay_Time);
915  log(std::string("Drive_Mode: "), xl_msgs_.Drive_Mode);
916  log(std::string("Operating_Mode: "), xl_msgs_.Operating_Mode);
917  log(std::string("Secondary_ID: "), xl_msgs_.Secondary_ID);
918  log(std::string("Protocol_Version: "), xl_msgs_.Protocol_Version);
919  log(std::string("Homing_Offset: "), xl_msgs_.Homing_Offset);
920  log(std::string("Moving_Threshold: "), xl_msgs_.Moving_Threshold);
921  log(std::string("Temperature_Limit: "), xl_msgs_.Temperature_Limit);
922  log(std::string("Max_Voltage_Limit: "), xl_msgs_.Max_Voltage_Limit);
923  log(std::string("Min_Voltage_Limit: "), xl_msgs_.Min_Voltage_Limit);
924  log(std::string("PWM_Limit: "), xl_msgs_.PWM_Limit);
925  log(std::string("Acceleration_Limit: "), xl_msgs_.Acceleration_Limit);
926  log(std::string("Velocity_Limit: "), xl_msgs_.Velocity_Limit);
927  log(std::string("Max_Position_Limit: "), xl_msgs_.Max_Position_Limit);
928  log(std::string("Min_Position_Limit: "), xl_msgs_.Min_Position_Limit);
929  log(std::string("Shutdown: "), xl_msgs_.Shutdown);
930  log(std::string(""));
931  log(std::string("< RAM >"));
932  log(std::string("Torque_Enable: "), xl_msgs_.Torque_Enable);
933  log(std::string("LED: "), xl_msgs_.LED);
934  log(std::string("Status_Return_Level: "), xl_msgs_.Status_Return_Level);
935  log(std::string("Registered_Instruction: "), xl_msgs_.Registered_Instruction);
936  log(std::string("Hardware_Error_Status: "), xl_msgs_.Hardware_Error_Status);
937  log(std::string("Velocity_I_Gain: "), xl_msgs_.Velocity_I_Gain);
938  log(std::string("Velocity_P_Gain: "), xl_msgs_.Velocity_P_Gain);
939  log(std::string("Position_D_Gain: "), xl_msgs_.Position_D_Gain);
940  log(std::string("Position_I_Gain: "), xl_msgs_.Position_I_Gain);
941  log(std::string("Position_P_Gain: "), xl_msgs_.Position_P_Gain);
942  log(std::string("Feedforward_2nd_Gain: "), xl_msgs_.Feedforward_2nd_Gain);
943  log(std::string("Feedforward_1st_Gain: "), xl_msgs_.Feedforward_1st_Gain);
944  log(std::string("Bus_Watchdog: "), xl_msgs_.Bus_Watchdog);
945  log(std::string("Goal_PWM: "), xl_msgs_.Goal_PWM);
946  log(std::string("Goal_Velocity: "), xl_msgs_.Goal_Velocity);
947  log(std::string("Profile_Acceleration: "), xl_msgs_.Profile_Acceleration);
948  log(std::string("Profile_Velocity: "), xl_msgs_.Profile_Velocity);
949  log(std::string("Goal_Position: "), xl_msgs_.Goal_Position);
950  log(std::string("Realtime_Tick: "), xl_msgs_.Realtime_Tick);
951  log(std::string("Moving: "), xl_msgs_.Moving);
952  log(std::string("Moving_Status: "), xl_msgs_.Moving_Status);
953  log(std::string("Present_PWM: "), xl_msgs_.Present_PWM);
954  log(std::string("Present_Load: "), xl_msgs_.Present_Load);
955  log(std::string("Present_Velocity: "), xl_msgs_.Present_Velocity);
956  log(std::string("Present_Position: "), xl_msgs_.Present_Position);
957  log(std::string("Velocity_Trajectory: "), xl_msgs_.Velocity_Trajectory);
958  log(std::string("Position_Trajectory: "), xl_msgs_.Position_Trajectory);
959  log(std::string("Present_Input_Voltage: "), xl_msgs_.Present_Input_Voltage);
960  log(std::string("Present_Temperature: "), xl_msgs_.Present_Temperature);
961 }
962 
963 void QNode::XM()
964 {
965  log(std::string("< EEPROM >"));
966  log(std::string("Model_Number: "), xm_msgs_.Model_Number);
967  log(std::string("Firmware_Version: "), xm_msgs_.Firmware_Version);
968  log(std::string("ID: "), xm_msgs_.ID);
969  log(std::string("Baud_Rate: "), xm_msgs_.Baud_Rate);
970  log(std::string("Return_Delay_Time: "), xm_msgs_.Return_Delay_Time);
971  log(std::string("Drive_Mode: "), xm_msgs_.Drive_Mode);
972  log(std::string("Operating_Mode: "), xm_msgs_.Operating_Mode);
973  log(std::string("Secondary_ID: "), xm_msgs_.Secondary_ID);
974  log(std::string("Protocol_Version: "), xm_msgs_.Protocol_Version);
975  log(std::string("Homing_Offset: "), xm_msgs_.Homing_Offset);
976  log(std::string("Moving_Threshold: "), xm_msgs_.Moving_Threshold);
977  log(std::string("Temperature_Limit: "), xm_msgs_.Temperature_Limit);
978  log(std::string("Max_Voltage_Limit: "), xm_msgs_.Max_Voltage_Limit);
979  log(std::string("Min_Voltage_Limit: "), xm_msgs_.Min_Voltage_Limit);
980  log(std::string("PWM_Limit: "), xm_msgs_.PWM_Limit);
981  log(std::string("Current_Limit: "), xm_msgs_.Current_Limit);
982  log(std::string("Acceleration_Limit: "), xm_msgs_.Acceleration_Limit);
983  log(std::string("Velocity_Limit: "), xm_msgs_.Velocity_Limit);
984  log(std::string("Max_Position_Limit: "), xm_msgs_.Max_Position_Limit);
985  log(std::string("Min_Position_Limit: "), xm_msgs_.Min_Position_Limit);
986  log(std::string("Shutdown: "), xm_msgs_.Shutdown);
987  log(std::string(""));
988  log(std::string("< RAM >"));
989  log(std::string("Torque_Enable: "), xm_msgs_.Torque_Enable);
990  log(std::string("LED: "), xm_msgs_.LED);
991  log(std::string("Status_Return_Level: "), xm_msgs_.Status_Return_Level);
992  log(std::string("Registered_Instruction: "), xm_msgs_.Registered_Instruction);
993  log(std::string("Hardware_Error_Status: "), xm_msgs_.Hardware_Error_Status);
994  log(std::string("Velocity_I_Gain: "), xm_msgs_.Velocity_I_Gain);
995  log(std::string("Velocity_P_Gain: "), xm_msgs_.Velocity_P_Gain);
996  log(std::string("Position_D_Gain: "), xm_msgs_.Position_D_Gain);
997  log(std::string("Position_I_Gain: "), xm_msgs_.Position_I_Gain);
998  log(std::string("Position_P_Gain: "), xm_msgs_.Position_P_Gain);
999  log(std::string("Feedforward_2nd_Gain: "), xm_msgs_.Feedforward_2nd_Gain);
1000  log(std::string("Feedforward_1st_Gain: "), xm_msgs_.Feedforward_1st_Gain);
1001  log(std::string("Bus_Watchdog: "), xm_msgs_.Bus_Watchdog);
1002  log(std::string("Goal_PWM: "), xm_msgs_.Goal_PWM);
1003  log(std::string("Goal_Current: "), xm_msgs_.Goal_Current);
1004  log(std::string("Goal_Velocity: "), xm_msgs_.Goal_Velocity);
1005  log(std::string("Profile_Acceleration: "), xm_msgs_.Profile_Acceleration);
1006  log(std::string("Profile_Velocity: "), xm_msgs_.Profile_Velocity);
1007  log(std::string("Goal_Position: "), xm_msgs_.Goal_Position);
1008  log(std::string("Realtime_Tick: "), xm_msgs_.Realtime_Tick);
1009  log(std::string("Moving: "), xm_msgs_.Moving);
1010  log(std::string("Moving_Status: "), xm_msgs_.Moving_Status);
1011  log(std::string("Present_PWM: "), xm_msgs_.Present_PWM);
1012  log(std::string("Present_Current: "), xm_msgs_.Present_Current);
1013  log(std::string("Present_Velocity: "), xm_msgs_.Present_Velocity);
1014  log(std::string("Present_Position: "), xm_msgs_.Present_Position);
1015  log(std::string("Velocity_Trajectory: "), xm_msgs_.Velocity_Trajectory);
1016  log(std::string("Position_Trajectory: "), xm_msgs_.Position_Trajectory);
1017  log(std::string("Present_Input_Voltage: "), xm_msgs_.Present_Input_Voltage);
1018  log(std::string("Present_Temperature: "), xm_msgs_.Present_Temperature);
1019 }
1020 
1022 {
1023  log(std::string("< EEPROM >"));
1024  log(std::string("Model_Number: "), xmext_msgs_.Model_Number);
1025  log(std::string("Firmware_Version: "), xmext_msgs_.Firmware_Version);
1026  log(std::string("ID: "), xmext_msgs_.ID);
1027  log(std::string("Baud_Rate: "), xmext_msgs_.Baud_Rate);
1028  log(std::string("Return_Delay_Time: "), xmext_msgs_.Return_Delay_Time);
1029  log(std::string("Drive_Mode: "), xmext_msgs_.Drive_Mode);
1030  log(std::string("Operating_Mode: "), xmext_msgs_.Operating_Mode);
1031  log(std::string("Secondary_ID: "), xmext_msgs_.Secondary_ID);
1032  log(std::string("Protocol_Version: "), xmext_msgs_.Protocol_Version);
1033  log(std::string("Homing_Offset: "), xmext_msgs_.Homing_Offset);
1034  log(std::string("Moving_Threshold: "), xmext_msgs_.Moving_Threshold);
1035  log(std::string("Temperature_Limit: "), xmext_msgs_.Temperature_Limit);
1036  log(std::string("Max_Voltage_Limit: "), xmext_msgs_.Max_Voltage_Limit);
1037  log(std::string("Min_Voltage_Limit: "), xmext_msgs_.Min_Voltage_Limit);
1038  log(std::string("PWM_Limit: "), xmext_msgs_.PWM_Limit);
1039  log(std::string("Current_Limit: "), xmext_msgs_.Current_Limit);
1040  log(std::string("Acceleration_Limit: "), xmext_msgs_.Acceleration_Limit);
1041  log(std::string("Velocity_Limit: "), xmext_msgs_.Velocity_Limit);
1042  log(std::string("Max_Position_Limit: "), xmext_msgs_.Max_Position_Limit);
1043  log(std::string("Min_Position_Limit: "), xmext_msgs_.Min_Position_Limit);
1044  log(std::string("External_Port_Mode_1: "), xmext_msgs_.External_Port_Mode_1);
1045  log(std::string("External_Port_Mode_2: "), xmext_msgs_.External_Port_Mode_2);
1046  log(std::string("External_Port_Mode_3: "), xmext_msgs_.External_Port_Mode_3);
1047  log(std::string("Shutdown: "), xmext_msgs_.Shutdown);
1048  log(std::string(""));
1049  log(std::string("< RAM >"));
1050  log(std::string("Torque_Enable: "), xmext_msgs_.Torque_Enable);
1051  log(std::string("LED: "), xmext_msgs_.LED);
1052  log(std::string("Status_Return_Level: "), xmext_msgs_.Status_Return_Level);
1053  log(std::string("Registered_Instruction: "), xmext_msgs_.Registered_Instruction);
1054  log(std::string("Hardware_Error_Status: "), xmext_msgs_.Hardware_Error_Status);
1055  log(std::string("Velocity_I_Gain: "), xmext_msgs_.Velocity_I_Gain);
1056  log(std::string("Velocity_P_Gain: "), xmext_msgs_.Velocity_P_Gain);
1057  log(std::string("Position_D_Gain: "), xmext_msgs_.Position_D_Gain);
1058  log(std::string("Position_I_Gain: "), xmext_msgs_.Position_I_Gain);
1059  log(std::string("Position_P_Gain: "), xmext_msgs_.Position_P_Gain);
1060  log(std::string("Feedforward_2nd_Gain: "), xmext_msgs_.Feedforward_2nd_Gain);
1061  log(std::string("Feedforward_1st_Gain: "), xmext_msgs_.Feedforward_1st_Gain);
1062  log(std::string("Bus_Watchdog: "), xmext_msgs_.Bus_Watchdog);
1063  log(std::string("Goal_PWM: "), xmext_msgs_.Goal_PWM);
1064  log(std::string("Goal_Current: "), xmext_msgs_.Goal_Current);
1065  log(std::string("Goal_Velocity: "), xmext_msgs_.Goal_Velocity);
1066  log(std::string("Profile_Acceleration: "), xmext_msgs_.Profile_Acceleration);
1067  log(std::string("Profile_Velocity: "), xmext_msgs_.Profile_Velocity);
1068  log(std::string("Goal_Position: "), xmext_msgs_.Goal_Position);
1069  log(std::string("Realtime_Tick: "), xmext_msgs_.Realtime_Tick);
1070  log(std::string("Moving: "), xmext_msgs_.Moving);
1071  log(std::string("Moving_Status: "), xmext_msgs_.Moving_Status);
1072  log(std::string("Present_PWM: "), xmext_msgs_.Present_PWM);
1073  log(std::string("Present_Current: "), xmext_msgs_.Present_Current);
1074  log(std::string("Present_Velocity: "), xmext_msgs_.Present_Velocity);
1075  log(std::string("Present_Position: "), xmext_msgs_.Present_Position);
1076  log(std::string("Velocity_Trajectory: "), xmext_msgs_.Velocity_Trajectory);
1077  log(std::string("Position_Trajectory: "), xmext_msgs_.Position_Trajectory);
1078  log(std::string("Present_Input_Voltage: "), xmext_msgs_.Present_Input_Voltage);
1079  log(std::string("Present_Temperature: "), xmext_msgs_.Present_Temperature);
1080 }
1081 
1083 {
1084  log(std::string("< EEPROM >"));
1085  log(std::string("Model_Number: "), xh_msgs_.Model_Number);
1086  log(std::string("Firmware_Version: "), xh_msgs_.Firmware_Version);
1087  log(std::string("ID: "), xh_msgs_.ID);
1088  log(std::string("Baud_Rate: "), xh_msgs_.Baud_Rate);
1089  log(std::string("Return_Delay_Time: "), xh_msgs_.Return_Delay_Time);
1090  log(std::string("Drive_Mode: "), xh_msgs_.Drive_Mode);
1091  log(std::string("Operating_Mode: "), xh_msgs_.Operating_Mode);
1092  log(std::string("Secondary_ID: "), xh_msgs_.Secondary_ID);
1093  log(std::string("Protocol_Version: "), xh_msgs_.Protocol_Version);
1094  log(std::string("Homing_Offset: "), xh_msgs_.Homing_Offset);
1095  log(std::string("Moving_Threshold: "), xh_msgs_.Moving_Threshold);
1096  log(std::string("Temperature_Limit: "), xh_msgs_.Temperature_Limit);
1097  log(std::string("Max_Voltage_Limit: "), xh_msgs_.Max_Voltage_Limit);
1098  log(std::string("Min_Voltage_Limit: "), xh_msgs_.Min_Voltage_Limit);
1099  log(std::string("PWM_Limit: "), xh_msgs_.PWM_Limit);
1100  log(std::string("Current_Limit: "), xh_msgs_.Current_Limit);
1101  log(std::string("Acceleration_Limit: "), xh_msgs_.Acceleration_Limit);
1102  log(std::string("Velocity_Limit: "), xh_msgs_.Velocity_Limit);
1103  log(std::string("Max_Position_Limit: "), xh_msgs_.Max_Position_Limit);
1104  log(std::string("Min_Position_Limit: "), xh_msgs_.Min_Position_Limit);
1105  log(std::string("Shutdown: "), xh_msgs_.Shutdown);
1106  log(std::string(""));
1107  log(std::string("< RAM >"));
1108  log(std::string("Torque_Enable: "), xh_msgs_.Torque_Enable);
1109  log(std::string("LED: "), xh_msgs_.LED);
1110  log(std::string("Status_Return_Level: "), xh_msgs_.Status_Return_Level);
1111  log(std::string("Registered_Instruction: "), xh_msgs_.Registered_Instruction);
1112  log(std::string("Hardware_Error_Status: "), xh_msgs_.Hardware_Error_Status);
1113  log(std::string("Velocity_I_Gain: "), xh_msgs_.Velocity_I_Gain);
1114  log(std::string("Velocity_P_Gain: "), xh_msgs_.Velocity_P_Gain);
1115  log(std::string("Position_D_Gain: "), xh_msgs_.Position_D_Gain);
1116  log(std::string("Position_I_Gain: "), xh_msgs_.Position_I_Gain);
1117  log(std::string("Position_P_Gain: "), xh_msgs_.Position_P_Gain);
1118  log(std::string("Feedforward_2nd_Gain: "), xh_msgs_.Feedforward_2nd_Gain);
1119  log(std::string("Feedforward_1st_Gain: "), xh_msgs_.Feedforward_1st_Gain);
1120  log(std::string("Bus_Watchdog: "), xh_msgs_.Bus_Watchdog);
1121  log(std::string("Goal_PWM: "), xh_msgs_.Goal_PWM);
1122  log(std::string("Goal_Current: "), xh_msgs_.Goal_Current);
1123  log(std::string("Goal_Velocity: "), xh_msgs_.Goal_Velocity);
1124  log(std::string("Profile_Acceleration: "), xh_msgs_.Profile_Acceleration);
1125  log(std::string("Profile_Velocity: "), xh_msgs_.Profile_Velocity);
1126  log(std::string("Goal_Position: "), xh_msgs_.Goal_Position);
1127  log(std::string("Realtime_Tick: "), xh_msgs_.Realtime_Tick);
1128  log(std::string("Moving: "), xh_msgs_.Moving);
1129  log(std::string("Moving_Status: "), xh_msgs_.Moving_Status);
1130  log(std::string("Present_PWM: "), xh_msgs_.Present_PWM);
1131  log(std::string("Present_Current: "), xh_msgs_.Present_Current);
1132  log(std::string("Present_Velocity: "), xh_msgs_.Present_Velocity);
1133  log(std::string("Present_Position: "), xh_msgs_.Present_Position);
1134  log(std::string("Velocity_Trajectory: "), xh_msgs_.Velocity_Trajectory);
1135  log(std::string("Position_Trajectory: "), xh_msgs_.Position_Trajectory);
1136  log(std::string("Present_Input_Voltage: "), xh_msgs_.Present_Input_Voltage);
1137  log(std::string("Present_Temperature: "), xh_msgs_.Present_Temperature);
1138 }
1139 
1141 {
1142  log(std::string("< EEPROM >"));
1143  log(std::string("Model_Number: "), pro_msgs_.Model_Number);
1144  log(std::string("Firmware_Version: "), pro_msgs_.Firmware_Version);
1145  log(std::string("ID: "), pro_msgs_.ID);
1146  log(std::string("Baud_Rate: "), pro_msgs_.Baud_Rate);
1147  log(std::string("Return_Delay_Time: "), pro_msgs_.Return_Delay_Time);
1148  log(std::string("Operating_Mode: "), pro_msgs_.Operating_Mode);
1149  log(std::string("Moving_Threshold: "), pro_msgs_.Moving_Threshold);
1150  log(std::string("Temperature_Limit: "), pro_msgs_.Temperature_Limit);
1151  log(std::string("Max_Voltage_Limit: "), pro_msgs_.Max_Voltage_Limit);
1152  log(std::string("Min_Voltage_Limit: "), pro_msgs_.Min_Voltage_Limit);
1153  log(std::string("Acceleration_Limit: "), pro_msgs_.Acceleration_Limit);
1154  log(std::string("Torque_Limit: "), pro_msgs_.Torque_Limit);
1155  log(std::string("Velocity_Limit: "), pro_msgs_.Velocity_Limit);
1156  log(std::string("Max_Position_Limit: "), pro_msgs_.Max_Position_Limit);
1157  log(std::string("Min_Position_Limit: "), pro_msgs_.Min_Position_Limit);
1158  log(std::string("External_Port_Mode_1: "), pro_msgs_.External_Port_Mode_1);
1159  log(std::string("External_Port_Mode_2: "), pro_msgs_.External_Port_Mode_2);
1160  log(std::string("External_Port_Mode_3: "), pro_msgs_.External_Port_Mode_3);
1161  log(std::string("External_Port_Mode_4: "), pro_msgs_.External_Port_Mode_4);
1162  log(std::string("Shutdown: "), pro_msgs_.Shutdown);
1163  log(std::string(""));
1164  log(std::string("< RAM >"));
1165  log(std::string("Torque_Enable: "), pro_msgs_.Torque_Enable);
1166  log(std::string("LED_RED: "), pro_msgs_.LED_RED);
1167  log(std::string("LED_GREEN: "), pro_msgs_.LED_GREEN);
1168  log(std::string("LED_BLUE: "), pro_msgs_.LED_BLUE);
1169  log(std::string("Velocity_I_Gain: "), pro_msgs_.Velocity_I_Gain);
1170  log(std::string("Velocity_P_Gain: "), pro_msgs_.Velocity_P_Gain);
1171  log(std::string("Position_P_Gain: "), pro_msgs_.Position_P_Gain);
1172  log(std::string("Goal_Position: "), pro_msgs_.Goal_Position);
1173  log(std::string("Goal_Velocity: "), pro_msgs_.Goal_Velocity);
1174  log(std::string("Goal_Torque: "), pro_msgs_.Goal_Torque);
1175  log(std::string("Moving: "), pro_msgs_.Moving);
1176  log(std::string("Present_Position: "), pro_msgs_.Present_Position);
1177  log(std::string("Present_Velocity: "), pro_msgs_.Present_Velocity);
1178  log(std::string("Present_Current: "), pro_msgs_.Present_Current);
1179  log(std::string("Present_Input_Voltage: "), pro_msgs_.Present_Input_Voltage);
1180  log(std::string("Present_Temperature: "), pro_msgs_.Present_Temperature);
1181  log(std::string("Registered_Instruction: "), pro_msgs_.Registered_Instruction);
1182  log(std::string("Status_Return_Level: "), pro_msgs_.Status_Return_Level);
1183  log(std::string("Hardware_Error_Status: "), pro_msgs_.Hardware_Error_Status);
1184 }
1185 
1187 {
1188  log(std::string("< EEPROM >"));
1189  log(std::string("Model_Number: "), proext_msgs_.Model_Number);
1190  log(std::string("Firmware_Version: "), proext_msgs_.Firmware_Version);
1191  log(std::string("ID: "), proext_msgs_.ID);
1192  log(std::string("Baud_Rate: "), proext_msgs_.Baud_Rate);
1193  log(std::string("Return_Delay_Time: "), proext_msgs_.Return_Delay_Time);
1194  log(std::string("Operating_Mode: "), proext_msgs_.Operating_Mode);
1195  log(std::string("Homing_Offset: "), proext_msgs_.Homing_Offset);
1196  log(std::string("Moving_Threshold: "), proext_msgs_.Moving_Threshold);
1197  log(std::string("Temperature_Limit: "), proext_msgs_.Temperature_Limit);
1198  log(std::string("Max_Voltage_Limit: "), proext_msgs_.Max_Voltage_Limit);
1199  log(std::string("Min_Voltage_Limit: "), proext_msgs_.Min_Voltage_Limit);
1200  log(std::string("Acceleration_Limit: "), proext_msgs_.Acceleration_Limit);
1201  log(std::string("Torque_Limit: "), proext_msgs_.Torque_Limit);
1202  log(std::string("Velocity_Limit: "), proext_msgs_.Velocity_Limit);
1203  log(std::string("Max_Position_Limit: "), proext_msgs_.Max_Position_Limit);
1204  log(std::string("Min_Position_Limit: "), proext_msgs_.Min_Position_Limit);
1205  log(std::string("External_Port_Mode_1: "), proext_msgs_.External_Port_Mode_1);
1206  log(std::string("External_Port_Mode_2: "), proext_msgs_.External_Port_Mode_2);
1207  log(std::string("External_Port_Mode_3: "), proext_msgs_.External_Port_Mode_3);
1208  log(std::string("External_Port_Mode_4: "), proext_msgs_.External_Port_Mode_4);
1209  log(std::string("Shutdown: "), proext_msgs_.Shutdown);
1210  log(std::string(""));
1211  log(std::string("< RAM >"));
1212  log(std::string("Torque_Enable: "), proext_msgs_.Torque_Enable);
1213  log(std::string("LED_RED: "), proext_msgs_.LED_RED);
1214  log(std::string("LED_GREEN: "), proext_msgs_.LED_GREEN);
1215  log(std::string("LED_BLUE: "), proext_msgs_.LED_BLUE);
1216  log(std::string("Velocity_I_Gain: "), proext_msgs_.Velocity_I_Gain);
1217  log(std::string("Velocity_P_Gain: "), proext_msgs_.Velocity_P_Gain);
1218  log(std::string("Position_P_Gain: "), proext_msgs_.Position_P_Gain);
1219  log(std::string("Goal_Position: "), proext_msgs_.Goal_Position);
1220  log(std::string("Goal_Velocity: "), proext_msgs_.Goal_Velocity);
1221  log(std::string("Goal_Torque: "), proext_msgs_.Goal_Torque);
1222  log(std::string("Moving: "), proext_msgs_.Moving);
1223  log(std::string("Present_Position: "), proext_msgs_.Present_Position);
1224  log(std::string("Present_Velocity: "), proext_msgs_.Present_Velocity);
1225  log(std::string("Present_Current: "), proext_msgs_.Present_Current);
1226  log(std::string("Present_Input_Voltage: "), proext_msgs_.Present_Input_Voltage);
1227  log(std::string("Present_Temperature: "), proext_msgs_.Present_Temperature);
1228  log(std::string("Registered_Instruction: "), proext_msgs_.Registered_Instruction);
1229  log(std::string("Status_Return_Level: "), proext_msgs_.Status_Return_Level);
1230  log(std::string("Hardware_Error_Status: "), proext_msgs_.Hardware_Error_Status);
1231 }
1232 
1233 void QNode::AXStatusMsgCallback(const dynamixel_workbench_msgs::AX::ConstPtr &msg)
1234 {
1235  pthread_mutex_lock(&mutex);
1236  ax_msgs_ = *msg;
1237  pthread_mutex_unlock(&mutex);
1238 }
1239 
1240 void QNode::RXStatusMsgCallback(const dynamixel_workbench_msgs::RX::ConstPtr &msg)
1241 {
1242  pthread_mutex_lock(&mutex);
1243  rx_msgs_ = *msg;
1244  pthread_mutex_unlock(&mutex);
1245 }
1246 
1247 void QNode::MXStatusMsgCallback(const dynamixel_workbench_msgs::MX::ConstPtr &msg)
1248 {
1249  pthread_mutex_lock(&mutex);
1250  mx_msgs_ = *msg;
1251  pthread_mutex_unlock(&mutex);
1252 }
1253 
1254 void QNode::MXExtStatusMsgCallback(const dynamixel_workbench_msgs::MXExt::ConstPtr &msg)
1255 {
1256  pthread_mutex_lock(&mutex);
1257  mxext_msgs_ = *msg;
1258  pthread_mutex_unlock(&mutex);
1259 }
1260 
1261 void QNode::MX2StatusMsgCallback(const dynamixel_workbench_msgs::MX2::ConstPtr &msg)
1262 {
1263  pthread_mutex_lock(&mutex);
1264  mx2_msgs_ = *msg;
1265  pthread_mutex_unlock(&mutex);
1266 }
1267 
1268 void QNode::MX2ExtStatusMsgCallback(const dynamixel_workbench_msgs::MX2Ext::ConstPtr &msg)
1269 {
1270  pthread_mutex_lock(&mutex);
1271  mx2ext_msgs_ = *msg;
1272  pthread_mutex_unlock(&mutex);
1273 }
1274 
1275 void QNode::EXStatusMsgCallback(const dynamixel_workbench_msgs::EX::ConstPtr &msg)
1276 {
1277  pthread_mutex_lock(&mutex);
1278  ex_msgs_ = *msg;
1279  pthread_mutex_unlock(&mutex);
1280 }
1281 
1282 void QNode::XL320StatusMsgCallback(const dynamixel_workbench_msgs::XL320::ConstPtr &msg)
1283 {
1284  pthread_mutex_lock(&mutex);
1285  xl320_msgs_ = *msg;
1286  pthread_mutex_unlock(&mutex);
1287 }
1288 
1289 void QNode::XLStatusMsgCallback(const dynamixel_workbench_msgs::XL::ConstPtr &msg)
1290 {
1291  pthread_mutex_lock(&mutex);
1292  xl_msgs_ = *msg;
1293  pthread_mutex_unlock(&mutex);
1294 }
1295 
1296 void QNode::XMStatusMsgCallback(const dynamixel_workbench_msgs::XM::ConstPtr &msg)
1297 {
1298  pthread_mutex_lock(&mutex);
1299  xm_msgs_ = *msg;
1300  pthread_mutex_unlock(&mutex);
1301 }
1302 
1303 void QNode::XMExtStatusMsgCallback(const dynamixel_workbench_msgs::XMExt::ConstPtr &msg)
1304 {
1305  pthread_mutex_lock(&mutex);
1306  xmext_msgs_ = *msg;
1307  pthread_mutex_unlock(&mutex);
1308 }
1309 
1310 void QNode::XHStatusMsgCallback(const dynamixel_workbench_msgs::XH::ConstPtr &msg)
1311 {
1312  pthread_mutex_lock(&mutex);
1313  xh_msgs_ = *msg;
1314  pthread_mutex_unlock(&mutex);
1315 }
1316 
1317 void QNode::PROStatusMsgCallback(const dynamixel_workbench_msgs::PRO::ConstPtr &msg)
1318 {
1319  pthread_mutex_lock(&mutex);
1320  pro_msgs_ = *msg;
1321  pthread_mutex_unlock(&mutex);
1322 }
1323 
1324 void QNode::PROExtStatusMsgCallback(const dynamixel_workbench_msgs::PROExt::ConstPtr &msg)
1325 {
1326  pthread_mutex_lock(&mutex);
1327  proext_msgs_ = *msg;
1328  pthread_mutex_unlock(&mutex);
1329 }
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
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void EXStatusMsgCallback(const dynamixel_workbench_msgs::EX::ConstPtr &msg)
Definition: qnode.cpp:1275
ROSCPP_DECL bool check()
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
ROSCPP_DECL void start()
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
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool sendRebootMsg(void)
Definition: qnode.cpp:352
bool call(MReq &req, MRes &res)
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
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
ROSCPP_DECL bool ok()
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 sleep()
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)
ROSCPP_DECL bool isStarted()
ros::Subscriber dynamixel_status_msg_sub_
Definition: qnode.hpp:134
dynamixel_workbench_msgs::MX2Ext mx2ext_msgs_
Definition: qnode.hpp:151
ROSCPP_DECL void shutdown()
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
ROSCPP_DECL void spinOnce()
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
ROSCPP_DECL void waitForShutdown()


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