24 #include <std_msgs/String.h> 25 #include "../include/dynamixel_workbench_single_manager_gui/qnode.hpp" 27 using namespace qnode;
64 mutex = PTHREAD_MUTEX_INITIALIZER;
72 dynamixel_workbench_msgs::DynamixelCommand set_dynamixel_command;
74 set_dynamixel_command.request.command = cmd;
75 set_dynamixel_command.request.addr_name = addr;
76 set_dynamixel_command.request.value = value;
80 if (!set_dynamixel_command.response.comm_result)
105 dynamixel_workbench_msgs::DynamixelCommand set_dynamixel_command;
107 if (protocol_version == 1.0)
109 if (index ==
"position_control")
116 else if (index ==
"velocity_control")
123 else if (index ==
"extended_position_control")
125 if (
sendCommandMsg(
"addr",
"CW_Angle_Limit", value_of_max_radian_position) &&
sendCommandMsg(
"addr",
"CCW_Angle_Limit", value_of_max_radian_position))
133 if (model_name.find(
"MX") != std::string::npos)
135 if (model_name.find(
"MX-28-2") != std::string::npos)
137 if (index ==
"velocity_control")
144 else if (index ==
"position_control")
151 else if (index ==
"extended_position_control")
158 else if (index ==
"pwm_control")
166 else if (model_name.find(
"MX-64-2") != std::string::npos ||
167 model_name.find(
"MX-106-2") != std::string::npos )
169 if (index ==
"current_control")
176 else if (index ==
"velocity_control")
183 else if (index ==
"position_control")
190 else if (index ==
"extended_position_control")
197 else if (index ==
"current_based_position_control")
204 else if (index ==
"pwm_control")
213 if (model_name.find(
"XL") != std::string::npos)
215 if (model_name.find(
"XL-320") != std::string::npos)
217 if (index ==
"position_control")
224 else if (index ==
"velocity_control")
232 else if (model_name.find(
"XL430-W250") != std::string::npos)
234 if (index ==
"velocity_control")
241 else if (index ==
"position_control")
248 else if (index ==
"extended_position_control")
255 else if (index ==
"pwm_control")
264 if (model_name.find(
"XM") != std::string::npos ||
265 model_name.find(
"XH") != std::string::npos )
267 if (index ==
"current_control")
274 else if (index ==
"velocity_control")
281 else if (index ==
"position_control")
288 else if (index ==
"extended_position_control")
295 else if (index ==
"current_based_position_control")
302 else if (index ==
"pwm_control")
310 else if (model_name.find(
"PRO") != std::string::npos)
312 if (index ==
"torque_control")
319 else if (index ==
"velocity_control")
326 else if (index ==
"position_control")
333 else if (index ==
"extended_position_control")
391 dynamixel_workbench_msgs::GetDynamixelInfo get_dynamixel_info;
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;
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;
428 else if (
dynamixel_info_.model_name.find(
"MX-64-2") != std::string::npos ||
434 else if (
dynamixel_info_.model_name.find(
"MX-12W") != std::string::npos ||
440 else if (
dynamixel_info_.model_name.find(
"MX-64") != std::string::npos ||
459 else if (
dynamixel_info_.model_name.find(
"XL430-W250") != std::string::npos)
467 if (
dynamixel_info_.model_name.find(
"XM430-W210") != std::string::npos ||
473 else if (
dynamixel_info_.model_name.find(
"XM540-W150") != std::string::npos ||
487 if (
dynamixel_info_.model_name.find(
"PRO_L42_10_S300_R") != std::string::npos)
510 std::cout <<
"ROS shutdown, proceeding to close the gui." << std::endl;
519 std::stringstream logging_model_msg;
521 logging_model_msg << msg << sender;
523 QVariant new_row(QString(logging_model_msg.str().c_str()));
534 std::stringstream logging_model_msg;
536 logging_model_msg << msg;
538 QVariant new_row(QString(logging_model_msg.str().c_str()));
546 pthread_mutex_lock(&
mutex);
548 pthread_mutex_unlock(&
mutex);
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);
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);
569 log(std::string(
""));
570 log(std::string(
"< RAM >"));
571 log(std::string(
"Torque_Enable: "),
ax_msgs_.Torque_Enable);
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);
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);
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);
608 log(std::string(
""));
609 log(std::string(
"< RAM >"));
610 log(std::string(
"Torque_Enable: "),
rx_msgs_.Torque_Enable);
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);
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);
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);
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);
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);
668 log(std::string(
"Goal_Acceleration: "),
mx_msgs_.Goal_Acceleration);
673 log(std::string(
"< EEPROM >"));
675 log(std::string(
"Firmware_Version: "),
mxext_msgs_.Firmware_Version);
678 log(std::string(
"Return_Delay_Time: "),
mxext_msgs_.Return_Delay_Time);
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);
685 log(std::string(
"Status_Return_Level: "),
mxext_msgs_.Status_Return_Level);
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 >"));
700 log(std::string(
"Present_Position: "),
mxext_msgs_.Present_Position);
703 log(std::string(
"Present_Voltage: "),
mxext_msgs_.Present_Voltage);
704 log(std::string(
"Present_Temperature: "),
mxext_msgs_.Present_Temperature);
710 log(std::string(
"Torque_Control_Mode_Enable: "),
mxext_msgs_.Torque_Control_Mode_Enable);
712 log(std::string(
"Goal_Acceleration: "),
mxext_msgs_.Goal_Acceleration);
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);
722 log(std::string(
"Return_Delay_Time: "),
mx2_msgs_.Return_Delay_Time);
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);
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);
738 log(std::string(
""));
739 log(std::string(
"< RAM >"));
740 log(std::string(
"Torque_Enable: "),
mx2_msgs_.Torque_Enable);
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);
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);
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);
773 log(std::string(
"< EEPROM >"));
778 log(std::string(
"Return_Delay_Time: "),
mx2ext_msgs_.Return_Delay_Time);
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);
790 log(std::string(
"Acceleration_Limit: "),
mx2ext_msgs_.Acceleration_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);
795 log(std::string(
""));
796 log(std::string(
"< RAM >"));
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);
807 log(std::string(
"Feedforward_2nd_Gain: "),
mx2ext_msgs_.Feedforward_2nd_Gain);
808 log(std::string(
"Feedforward_1st_Gain: "),
mx2ext_msgs_.Feedforward_1st_Gain);
812 log(std::string(
"Profile_Acceleration: "),
mx2ext_msgs_.Profile_Acceleration);
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);
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);
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);
846 log(std::string(
""));
847 log(std::string(
"< RAM >"));
848 log(std::string(
"Torque_Enable: "),
ex_msgs_.Torque_Enable);
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);
866 log(std::string(
"Sensored_Current: "),
ex_msgs_.Sensored_Current);
871 log(std::string(
"< EEPROM >"));
873 log(std::string(
"Firmware_Version: "),
xl320_msgs_.Firmware_Version);
876 log(std::string(
"Return_Delay_Time: "),
xl320_msgs_.Return_Delay_Time);
878 log(std::string(
"CCW_Angle_Limit: "),
xl320_msgs_.CCW_Angle_Limit);
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);
884 log(std::string(
"Status_Return_Level: "),
xl320_msgs_.Status_Return_Level);
886 log(std::string(
""));
887 log(std::string(
"< RAM >"));
896 log(std::string(
"Present_Position: "),
xl320_msgs_.Present_Position);
899 log(std::string(
"Present_Voltage: "),
xl320_msgs_.Present_Voltage);
900 log(std::string(
"Present_Temperature: "),
xl320_msgs_.Present_Temperature);
903 log(std::string(
"Hardware_Error_Status: "),
xl320_msgs_.Hardware_Error_Status);
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);
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);
930 log(std::string(
""));
931 log(std::string(
"< RAM >"));
932 log(std::string(
"Torque_Enable: "),
xl_msgs_.Torque_Enable);
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);
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);
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);
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);
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);
987 log(std::string(
""));
988 log(std::string(
"< RAM >"));
989 log(std::string(
"Torque_Enable: "),
xm_msgs_.Torque_Enable);
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);
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);
1023 log(std::string(
"< EEPROM >"));
1025 log(std::string(
"Firmware_Version: "),
xmext_msgs_.Firmware_Version);
1028 log(std::string(
"Return_Delay_Time: "),
xmext_msgs_.Return_Delay_Time);
1030 log(std::string(
"Operating_Mode: "),
xmext_msgs_.Operating_Mode);
1032 log(std::string(
"Protocol_Version: "),
xmext_msgs_.Protocol_Version);
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);
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);
1048 log(std::string(
""));
1049 log(std::string(
"< RAM >"));
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);
1066 log(std::string(
"Profile_Acceleration: "),
xmext_msgs_.Profile_Acceleration);
1067 log(std::string(
"Profile_Velocity: "),
xmext_msgs_.Profile_Velocity);
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);
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);
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);
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);
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);
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);
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);
1163 log(std::string(
""));
1164 log(std::string(
"< RAM >"));
1165 log(std::string(
"Torque_Enable: "),
pro_msgs_.Torque_Enable);
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);
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);
1188 log(std::string(
"< EEPROM >"));
1190 log(std::string(
"Firmware_Version: "),
proext_msgs_.Firmware_Version);
1193 log(std::string(
"Return_Delay_Time: "),
proext_msgs_.Return_Delay_Time);
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);
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);
1210 log(std::string(
""));
1211 log(std::string(
"< RAM >"));
1223 log(std::string(
"Present_Position: "),
proext_msgs_.Present_Position);
1224 log(std::string(
"Present_Velocity: "),
proext_msgs_.Present_Velocity);
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);
1235 pthread_mutex_lock(&
mutex);
1237 pthread_mutex_unlock(&
mutex);
1242 pthread_mutex_lock(&
mutex);
1244 pthread_mutex_unlock(&
mutex);
1249 pthread_mutex_lock(&
mutex);
1251 pthread_mutex_unlock(&
mutex);
1256 pthread_mutex_lock(&
mutex);
1258 pthread_mutex_unlock(&
mutex);
1263 pthread_mutex_lock(&
mutex);
1265 pthread_mutex_unlock(&
mutex);
1270 pthread_mutex_lock(&
mutex);
1272 pthread_mutex_unlock(&
mutex);
1277 pthread_mutex_lock(&
mutex);
1279 pthread_mutex_unlock(&
mutex);
1284 pthread_mutex_lock(&
mutex);
1286 pthread_mutex_unlock(&
mutex);
1291 pthread_mutex_lock(&
mutex);
1293 pthread_mutex_unlock(&
mutex);
1298 pthread_mutex_lock(&
mutex);
1300 pthread_mutex_unlock(&
mutex);
1305 pthread_mutex_lock(&
mutex);
1307 pthread_mutex_unlock(&
mutex);
1312 pthread_mutex_lock(&
mutex);
1314 pthread_mutex_unlock(&
mutex);
1319 pthread_mutex_lock(&
mutex);
1321 pthread_mutex_unlock(&
mutex);
1326 pthread_mutex_lock(&
mutex);
1328 pthread_mutex_unlock(&
mutex);
dynamixel_workbench_msgs::XL xl_msgs_
void PROStatusMsgCallback(const dynamixel_workbench_msgs::PRO::ConstPtr &msg)
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)
dynamixel_workbench_msgs::XH xh_msgs_
void PROExtStatusMsgCallback(const dynamixel_workbench_msgs::PROExt::ConstPtr &msg)
dynamixel_workbench_msgs::PROExt proext_msgs_
QStringListModel logging_model_
ros::ServiceClient dynamixel_info_client_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
dynamixel_workbench_msgs::MXExt mxext_msgs_
dynamixel_workbench_msgs::EX ex_msgs_
void XLStatusMsgCallback(const dynamixel_workbench_msgs::XL::ConstPtr &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
bool sendCommandMsg(std::string cmd, std::string addr="", int64_t value=0)
ros::ServiceClient dynamixel_command_client_
dynamixel_workbench_msgs::AX ax_msgs_
void RXStatusMsgCallback(const dynamixel_workbench_msgs::RX::ConstPtr &msg)
QNode(int argc, char **argv)
void XMExtStatusMsgCallback(const dynamixel_workbench_msgs::XMExt::ConstPtr &msg)
void XMStatusMsgCallback(const dynamixel_workbench_msgs::XM::ConstPtr &msg)
void log(const std::string &msg, int64_t sender)
void MX2StatusMsgCallback(const dynamixel_workbench_msgs::MX2::ConstPtr &msg)
dynamixel_workbench_msgs::XL320 xl320_msgs_
dynamixel_workbench_msgs::MX mx_msgs_
dynamixel_workbench_msgs::PRO pro_msgs_
bool sendSetBaudrateMsg(int64_t baud_rate)
dynamixel_workbench_msgs::XM xm_msgs_
dynamixel_workbench_msgs::RX rx_msgs_
dynamixel_workbench_msgs::DynamixelInfo dynamixel_info_
bool sendAddressValueMsg(std::string addr_name, int64_t value)
void initDynamixelStateSubscriber()
void MX2ExtStatusMsgCallback(const dynamixel_workbench_msgs::MX2Ext::ConstPtr &msg)
void(qnode::QNode::* dynamixelDataLogPtr)(void)
dynamixel_workbench_msgs::MX2 mx2_msgs_
void XL320StatusMsgCallback(const dynamixel_workbench_msgs::XL320::ConstPtr &msg)
bool sendTorqueMsg(int64_t onoff)
void MXStatusMsgCallback(const dynamixel_workbench_msgs::MX::ConstPtr &msg)
void MXExtStatusMsgCallback(const dynamixel_workbench_msgs::MXExt::ConstPtr &msg)
void updateDynamixelInfo(dynamixel_workbench_msgs::DynamixelInfo)
ROSCPP_DECL bool isStarted()
ros::Subscriber dynamixel_status_msg_sub_
dynamixel_workbench_msgs::MX2Ext mx2ext_msgs_
ROSCPP_DECL void shutdown()
dynamixel_workbench_msgs::XMExt xmext_msgs_
bool sendSetIdMsg(uint8_t set_id)
ROSCPP_DECL void spinOnce()
void AXStatusMsgCallback(const dynamixel_workbench_msgs::AX::ConstPtr &msg)
void writeReceivedDynamixelData()
void XHStatusMsgCallback(const dynamixel_workbench_msgs::XH::ConstPtr &msg)
bool sendSetOperatingModeMsg(std::string index, float protocol_version, std::string model_name, int32_t value_of_max_radian_position)
bool setPositionZeroMsg(int32_t zero_position)
ROSCPP_DECL void waitForShutdown()