test_tool_modbus.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "xarm_ros_client.h"
3 #include <xarm_driver.h>
4 
5 // Please run "export ROS_NAMESPACE=/xarm" first
6 
7 int main(int argc, char **argv)
8 {
9  ros::init(argc, argv, "xarm_modbus");
10  ros::NodeHandle nh;
11 
13  client.init(nh);
14 
15  int recv_bytes = 7;
16  unsigned char send_data[6] = {0x01,0x06,0x00,0x0A,0x00,0x03};
17  unsigned char * recv_data = new unsigned char [recv_bytes]{0};
18 
19  int ret = 0;
20  ros::Rate rate(10);
21 
22  ret = client.send_tool_modbus(send_data, 6, recv_data, recv_bytes);
23  fprintf(stderr, "ret = %d, recv_data: ", ret);
24 
25  for(int i=0; i<recv_bytes; i++)
26  {
27  fprintf(stderr, "%x\t", recv_data[i]);
28  }
29  fprintf(stderr, "\n");
30  rate.sleep();
31 
32  return 0;
33 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool sleep()
int send_tool_modbus(unsigned char *data, int send_len, unsigned char *recv_data=NULL, int recv_len=0)
void init(ros::NodeHandle &nh)


xarm_api
Author(s):
autogenerated on Sat May 8 2021 02:51:23