Public Member Functions | Private Attributes | List of all members
xarm_api::XArmROSClient Class Reference

#include <xarm_ros_client.h>

Public Member Functions

int clearErr (void)
 
int config_tool_modbus (int baud_rate, int time_out_ms)
 
int getErr (void)
 
int getGripperState (float *curr_pulse, int *curr_err)
 
int goHome (float jnt_vel_rad, float jnt_acc_rad=15)
 
int gripperConfig (float pulse_vel)
 
int gripperMove (float pulse)
 
void init (ros::NodeHandle &nh)
 
int motionEnable (short en)
 
int moveJoint (const std::vector< float > &joint_cmd, float jnt_vel_rad, float jnt_acc_rad=15)
 
int moveLine (const std::vector< float > &cart_cmd, float cart_vel_mm, float cart_acc_mm=500)
 
int moveLineB (int num_of_pnts, const std::vector< float > cart_cmds[], float cart_vel_mm, float cart_acc_mm=500, float radii=0)
 
int send_tool_modbus (unsigned char *data, int send_len, unsigned char *recv_data=NULL, int recv_len=0)
 
int setLoad (float mass, const std::vector< float > &center_of_mass)
 
int setMode (short mode)
 
int setServoCartisian (const std::vector< float > &cart_cmd)
 
int setServoJ (const std::vector< float > &joint_cmd)
 
int setState (short state)
 
int setTCPOffset (const std::vector< float > &tcp_offset)
 
int veloMoveJoint (const std::vector< float > &jnt_v, bool is_sync=true)
 
int veloMoveLine (const std::vector< float > &line_v, bool is_tool_coord=false)
 
 XArmROSClient ()
 
 ~XArmROSClient ()
 

Private Attributes

xarm_msgs::ConfigToolModbus cfg_modbus_msg_
 
ros::ServiceClient clear_err_client_
 
xarm_msgs::ClearErr clear_err_srv_
 
ros::ServiceClient config_modbus_client_
 
ros::ServiceClient get_err_client_
 
xarm_msgs::GetErr get_err_srv_
 
ros::ServiceClient go_home_client_
 
ros::ServiceClient gripper_config_client_
 
xarm_msgs::GripperConfig gripper_config_msg_
 
ros::ServiceClient gripper_move_client_
 
xarm_msgs::GripperMove gripper_move_msg_
 
ros::ServiceClient gripper_state_client_
 
xarm_msgs::GripperState gripper_state_msg_
 
ros::ServiceClient motion_ctrl_client_
 
ros::ServiceClient move_joint_client_
 
ros::ServiceClient move_line_client_
 
ros::ServiceClient move_lineb_client_
 
ros::ServiceClient move_servo_cart_client_
 
ros::ServiceClient move_servoj_client_
 
xarm_msgs::Move move_srv_
 
xarm_msgs::MoveVelo move_velo_srv_
 
ros::NodeHandle nh_
 
xarm_msgs::TCPOffset offset_srv_
 
ros::ServiceClient send_modbus_client_
 
xarm_msgs::Move servo_cart_msg_
 
xarm_msgs::Move servoj_msg_
 
xarm_msgs::SetAxis set_axis_srv_
 
xarm_msgs::SetInt16 set_int16_srv_
 
ros::ServiceClient set_load_client_
 
xarm_msgs::SetLoad set_load_srv_
 
xarm_msgs::SetToolModbus set_modbus_msg_
 
ros::ServiceClient set_mode_client_
 
ros::ServiceClient set_state_client_
 
ros::ServiceClient set_tcp_offset_client_
 
ros::ServiceClient velo_move_joint_client_
 
ros::ServiceClient velo_move_line_client_
 

Detailed Description

Definition at line 10 of file xarm_ros_client.h.

Constructor & Destructor Documentation

xarm_api::XArmROSClient::XArmROSClient ( )

Definition at line 11 of file xarm_ros_client.cpp.

xarm_api::XArmROSClient::~XArmROSClient ( )

Definition at line 12 of file xarm_ros_client.cpp.

Member Function Documentation

int xarm_api::XArmROSClient::clearErr ( void  )

Definition at line 99 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::config_tool_modbus ( int  baud_rate,
int  time_out_ms 
)

Definition at line 292 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::getErr ( void  )

Definition at line 114 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::getGripperState ( float *  curr_pulse,
int *  curr_err 
)

Definition at line 372 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::goHome ( float  jnt_vel_rad,
float  jnt_acc_rad = 15 
)

Definition at line 213 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::gripperConfig ( float  pulse_vel)

Definition at line 356 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::gripperMove ( float  pulse)

Definition at line 340 of file xarm_ros_client.cpp.

void xarm_api::XArmROSClient::init ( ros::NodeHandle nh)

Definition at line 14 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::motionEnable ( short  en)

Definition at line 51 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::moveJoint ( const std::vector< float > &  joint_cmd,
float  jnt_vel_rad,
float  jnt_acc_rad = 15 
)

Definition at line 230 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::moveLine ( const std::vector< float > &  cart_cmd,
float  cart_vel_mm,
float  cart_acc_mm = 500 
)

Definition at line 248 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::moveLineB ( int  num_of_pnts,
const std::vector< float >  cart_cmds[],
float  cart_vel_mm,
float  cart_acc_mm = 500,
float  radii = 0 
)

Definition at line 266 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::send_tool_modbus ( unsigned char *  data,
int  send_len,
unsigned char *  recv_data = NULL,
int  recv_len = 0 
)

Definition at line 307 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setLoad ( float  mass,
const std::vector< float > &  center_of_mass 
)

Definition at line 195 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setMode ( short  mode)

Definition at line 83 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setServoCartisian ( const std::vector< float > &  cart_cmd)

Definition at line 148 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setServoJ ( const std::vector< float > &  joint_cmd)

Definition at line 129 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setState ( short  state)

Definition at line 68 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::setTCPOffset ( const std::vector< float > &  tcp_offset)

Definition at line 168 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::veloMoveJoint ( const std::vector< float > &  jnt_v,
bool  is_sync = true 
)

Definition at line 388 of file xarm_ros_client.cpp.

int xarm_api::XArmROSClient::veloMoveLine ( const std::vector< float > &  line_v,
bool  is_tool_coord = false 
)

Definition at line 404 of file xarm_ros_client.cpp.

Member Data Documentation

xarm_msgs::ConfigToolModbus xarm_api::XArmROSClient::cfg_modbus_msg_
private

Definition at line 71 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::clear_err_client_
private

Definition at line 52 of file xarm_ros_client.h.

xarm_msgs::ClearErr xarm_api::XArmROSClient::clear_err_srv_
private

Definition at line 66 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::config_modbus_client_
private

Definition at line 54 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::get_err_client_
private

Definition at line 53 of file xarm_ros_client.h.

xarm_msgs::GetErr xarm_api::XArmROSClient::get_err_srv_
private

Definition at line 67 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::go_home_client_
private

Definition at line 44 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::gripper_config_client_
private

Definition at line 57 of file xarm_ros_client.h.

xarm_msgs::GripperConfig xarm_api::XArmROSClient::gripper_config_msg_
private

Definition at line 73 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::gripper_move_client_
private

Definition at line 56 of file xarm_ros_client.h.

xarm_msgs::GripperMove xarm_api::XArmROSClient::gripper_move_msg_
private

Definition at line 74 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::gripper_state_client_
private

Definition at line 58 of file xarm_ros_client.h.

xarm_msgs::GripperState xarm_api::XArmROSClient::gripper_state_msg_
private

Definition at line 75 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::motion_ctrl_client_
private

Definition at line 41 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::move_joint_client_
private

Definition at line 49 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::move_line_client_
private

Definition at line 48 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::move_lineb_client_
private

Definition at line 45 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::move_servo_cart_client_
private

Definition at line 47 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::move_servoj_client_
private

Definition at line 46 of file xarm_ros_client.h.

xarm_msgs::Move xarm_api::XArmROSClient::move_srv_
private

Definition at line 68 of file xarm_ros_client.h.

xarm_msgs::MoveVelo xarm_api::XArmROSClient::move_velo_srv_
private

Definition at line 76 of file xarm_ros_client.h.

ros::NodeHandle xarm_api::XArmROSClient::nh_
private

Definition at line 78 of file xarm_ros_client.h.

xarm_msgs::TCPOffset xarm_api::XArmROSClient::offset_srv_
private

Definition at line 64 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::send_modbus_client_
private

Definition at line 55 of file xarm_ros_client.h.

xarm_msgs::Move xarm_api::XArmROSClient::servo_cart_msg_
private

Definition at line 70 of file xarm_ros_client.h.

xarm_msgs::Move xarm_api::XArmROSClient::servoj_msg_
private

Definition at line 69 of file xarm_ros_client.h.

xarm_msgs::SetAxis xarm_api::XArmROSClient::set_axis_srv_
private

Definition at line 62 of file xarm_ros_client.h.

xarm_msgs::SetInt16 xarm_api::XArmROSClient::set_int16_srv_
private

Definition at line 63 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::set_load_client_
private

Definition at line 51 of file xarm_ros_client.h.

xarm_msgs::SetLoad xarm_api::XArmROSClient::set_load_srv_
private

Definition at line 65 of file xarm_ros_client.h.

xarm_msgs::SetToolModbus xarm_api::XArmROSClient::set_modbus_msg_
private

Definition at line 72 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::set_mode_client_
private

Definition at line 42 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::set_state_client_
private

Definition at line 43 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::set_tcp_offset_client_
private

Definition at line 50 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::velo_move_joint_client_
private

Definition at line 59 of file xarm_ros_client.h.

ros::ServiceClient xarm_api::XArmROSClient::velo_move_line_client_
private

Definition at line 60 of file xarm_ros_client.h.


The documentation for this class was generated from the following files:


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