1 #ifndef __XARM_ROS_CLIENT_H__ 2 #define __XARM_ROS_CLIENT_H__ 17 int motionEnable(
short en);
18 int setState(
short state);
19 int setMode(
short mode);
22 int setTCPOffset(
const std::vector<float>& tcp_offset);
23 int setLoad(
float mass,
const std::vector<float>& center_of_mass);
24 int setServoJ(
const std::vector<float>& joint_cmd);
25 int setServoCartisian(
const std::vector<float>& cart_cmd);
26 int goHome(
float jnt_vel_rad,
float jnt_acc_rad=15);
27 int moveJoint(
const std::vector<float>& joint_cmd,
float jnt_vel_rad,
float jnt_acc_rad=15);
28 int moveLine(
const std::vector<float>& cart_cmd,
float cart_vel_mm,
float cart_acc_mm=500);
29 int moveLineB(
int num_of_pnts,
const std::vector<float> cart_cmds[],
float cart_vel_mm,
float cart_acc_mm=500,
float radii=0);
30 int getGripperState(
float *curr_pulse,
int *curr_err);
31 int gripperConfig(
float pulse_vel);
32 int gripperMove(
float pulse);
34 int config_tool_modbus(
int baud_rate,
int time_out_ms);
35 int send_tool_modbus(
unsigned char* data,
int send_len,
unsigned char* recv_data=NULL,
int recv_len=0);
37 int veloMoveJoint(
const std::vector<float>& jnt_v,
bool is_sync =
true);
38 int veloMoveLine(
const std::vector<float>& line_v,
bool is_tool_coord =
false);
ros::ServiceClient move_joint_client_
xarm_msgs::SetToolModbus set_modbus_msg_
xarm_msgs::ConfigToolModbus cfg_modbus_msg_
ros::ServiceClient move_line_client_
ros::ServiceClient set_state_client_
void init(const M_string &remappings)
xarm_msgs::SetAxis set_axis_srv_
ros::ServiceClient move_servoj_client_
ros::ServiceClient velo_move_line_client_
ros::ServiceClient motion_ctrl_client_
xarm_msgs::MoveVelo move_velo_srv_
ros::ServiceClient config_modbus_client_
xarm_msgs::Move servo_cart_msg_
xarm_msgs::SetInt16 set_int16_srv_
xarm_msgs::GripperState gripper_state_msg_
xarm_msgs::GetErr get_err_srv_
ros::ServiceClient gripper_state_client_
xarm_msgs::ClearErr clear_err_srv_
ros::ServiceClient move_lineb_client_
xarm_msgs::Move move_srv_
xarm_msgs::TCPOffset offset_srv_
ros::ServiceClient set_load_client_
ros::ServiceClient gripper_config_client_
xarm_msgs::Move servoj_msg_
xarm_msgs::SetLoad set_load_srv_
ros::ServiceClient set_mode_client_
ros::ServiceClient move_servo_cart_client_
ros::ServiceClient gripper_move_client_
xarm_msgs::GripperMove gripper_move_msg_
ros::ServiceClient send_modbus_client_
ros::ServiceClient set_tcp_offset_client_
ros::ServiceClient clear_err_client_
ros::ServiceClient go_home_client_
ros::ServiceClient get_err_client_
ros::ServiceClient velo_move_joint_client_
xarm_msgs::GripperConfig gripper_config_msg_