19 #ifndef DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP 20 #define DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP 27 #include <QStringListModel> 32 #include "dynamixel_workbench_msgs/DynamixelCommand.h" 33 #include "dynamixel_workbench_msgs/GetDynamixelInfo.h" 34 #include "dynamixel_workbench_msgs/DynamixelInfo.h" 45 QNode(
int argc,
char** argv );
52 void log(
const std::string &msg, int64_t sender);
53 void log(
const std::string &msg);
103 bool sendSetOperatingModeMsg(std::string index,
float protocol_version, std::string model_name, int32_t value_of_max_radian_position);
117 bool sendCommandMsg(std::string cmd, std::string addr =
"", int64_t value = 0);
163 #endif //DYNAMIXEL_WORKBENCH_SINGLE_MANAGER_GUI_QNODE_HPP dynamixel_workbench_msgs::XL xl_msgs_
void PROStatusMsgCallback(const dynamixel_workbench_msgs::PRO::ConstPtr &msg)
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_
dynamixel_workbench_msgs::MXExt mxext_msgs_
dynamixel_workbench_msgs::EX ex_msgs_
void XLStatusMsgCallback(const dynamixel_workbench_msgs::XL::ConstPtr &msg)
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_
QStringListModel * loggingModel()
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)
ros::Subscriber dynamixel_status_msg_sub_
dynamixel_workbench_msgs::MX2Ext mx2ext_msgs_
dynamixel_workbench_msgs::XMExt xmext_msgs_
bool sendSetIdMsg(uint8_t set_id)
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)