#include <xarm_ros_client.h>
|
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 > ¢er_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 () |
|
Definition at line 10 of file xarm_ros_client.h.
xarm_api::XArmROSClient::XArmROSClient |
( |
| ) |
|
xarm_api::XArmROSClient::~XArmROSClient |
( |
| ) |
|
int xarm_api::XArmROSClient::clearErr |
( |
void |
| ) |
|
int xarm_api::XArmROSClient::config_tool_modbus |
( |
int |
baud_rate, |
|
|
int |
time_out_ms |
|
) |
| |
int xarm_api::XArmROSClient::getErr |
( |
void |
| ) |
|
int xarm_api::XArmROSClient::getGripperState |
( |
float * |
curr_pulse, |
|
|
int * |
curr_err |
|
) |
| |
int xarm_api::XArmROSClient::goHome |
( |
float |
jnt_vel_rad, |
|
|
float |
jnt_acc_rad = 15 |
|
) |
| |
int xarm_api::XArmROSClient::gripperConfig |
( |
float |
pulse_vel | ) |
|
int xarm_api::XArmROSClient::gripperMove |
( |
float |
pulse | ) |
|
int xarm_api::XArmROSClient::motionEnable |
( |
short |
en | ) |
|
int xarm_api::XArmROSClient::moveJoint |
( |
const std::vector< float > & |
joint_cmd, |
|
|
float |
jnt_vel_rad, |
|
|
float |
jnt_acc_rad = 15 |
|
) |
| |
int xarm_api::XArmROSClient::moveLine |
( |
const std::vector< float > & |
cart_cmd, |
|
|
float |
cart_vel_mm, |
|
|
float |
cart_acc_mm = 500 |
|
) |
| |
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 |
|
) |
| |
int xarm_api::XArmROSClient::send_tool_modbus |
( |
unsigned char * |
data, |
|
|
int |
send_len, |
|
|
unsigned char * |
recv_data = NULL , |
|
|
int |
recv_len = 0 |
|
) |
| |
int xarm_api::XArmROSClient::setLoad |
( |
float |
mass, |
|
|
const std::vector< float > & |
center_of_mass |
|
) |
| |
int xarm_api::XArmROSClient::setMode |
( |
short |
mode | ) |
|
int xarm_api::XArmROSClient::setServoCartisian |
( |
const std::vector< float > & |
cart_cmd | ) |
|
int xarm_api::XArmROSClient::setServoJ |
( |
const std::vector< float > & |
joint_cmd | ) |
|
int xarm_api::XArmROSClient::setState |
( |
short |
state | ) |
|
int xarm_api::XArmROSClient::setTCPOffset |
( |
const std::vector< float > & |
tcp_offset | ) |
|
int xarm_api::XArmROSClient::veloMoveJoint |
( |
const std::vector< float > & |
jnt_v, |
|
|
bool |
is_sync = true |
|
) |
| |
int xarm_api::XArmROSClient::veloMoveLine |
( |
const std::vector< float > & |
line_v, |
|
|
bool |
is_tool_coord = false |
|
) |
| |
xarm_msgs::ConfigToolModbus xarm_api::XArmROSClient::cfg_modbus_msg_ |
|
private |
xarm_msgs::ClearErr xarm_api::XArmROSClient::clear_err_srv_ |
|
private |
xarm_msgs::GetErr xarm_api::XArmROSClient::get_err_srv_ |
|
private |
xarm_msgs::GripperConfig xarm_api::XArmROSClient::gripper_config_msg_ |
|
private |
xarm_msgs::GripperMove xarm_api::XArmROSClient::gripper_move_msg_ |
|
private |
xarm_msgs::GripperState xarm_api::XArmROSClient::gripper_state_msg_ |
|
private |
xarm_msgs::Move xarm_api::XArmROSClient::move_srv_ |
|
private |
xarm_msgs::MoveVelo xarm_api::XArmROSClient::move_velo_srv_ |
|
private |
xarm_msgs::TCPOffset xarm_api::XArmROSClient::offset_srv_ |
|
private |
xarm_msgs::Move xarm_api::XArmROSClient::servo_cart_msg_ |
|
private |
xarm_msgs::Move xarm_api::XArmROSClient::servoj_msg_ |
|
private |
xarm_msgs::SetAxis xarm_api::XArmROSClient::set_axis_srv_ |
|
private |
xarm_msgs::SetInt16 xarm_api::XArmROSClient::set_int16_srv_ |
|
private |
xarm_msgs::SetLoad xarm_api::XArmROSClient::set_load_srv_ |
|
private |
xarm_msgs::SetToolModbus xarm_api::XArmROSClient::set_modbus_msg_ |
|
private |
The documentation for this class was generated from the following files: