our_control_api.h
Go to the documentation of this file.
00001 #ifndef OUR_CONTROL_API_V1_H
00002 #define OUR_CONTROL_API_V1_H
00003 
00004 #if defined(__WIN32__) || defined (WIN32)
00005 #define AUBOAPI_DLLSHARED_EXPORT __declspec(dllexport)
00006 #else
00007 #define AUBOAPI_DLLSHARED_EXPORT
00008 #endif
00009 
00010 
00011 #include "metaType.h"
00012 
00013 
00014 extern "C"
00015 {
00016 
00017 /***connect to server***/
00018 AUBOAPI_DLLSHARED_EXPORT int  login (const char *ip, int port, const char *userName, const char *password);
00019 
00020 /***disconnect ***/
00021 AUBOAPI_DLLSHARED_EXPORT int  logout_system();
00022 
00023 /***register for event callback function***/
00024 int  register_event_push_callback     (EventPushCallback ptr);
00025 
00026 /***register for realtime position callback function***/
00027 int  register_roadPoint_event_callback(RealTimeRoadPointEventCallback ptr);
00028 
00029 /***enable realtime position callback event***/
00030 int  enable_realtime_roadpoint_event();
00031 
00032 /***disable realtime position callback event***/
00033 int  disenable_realtime_roadpoint_event();
00034 
00035 
00036 /***joint move in joint space***/
00037 AUBOAPI_DLLSHARED_EXPORT int  robot_moveJ(robot_move_profile *move_profile, const our_robot_road_point *roadPoint);
00038 
00039 /***line move in tool pose space***/
00040 AUBOAPI_DLLSHARED_EXPORT int  robot_moveL(robot_move_profile *move_profile, const our_robot_road_point *roadPoint);
00041 
00042 /***track move in tool pose space***/
00043 AUBOAPI_DLLSHARED_EXPORT int  robot_moveP(robot_move_profile *move_profile, const our_robot_road_point *point_array,int len);
00044 
00045 /***line move to position(x,y,z)***/
00046 AUBOAPI_DLLSHARED_EXPORT int  robot_moveLTo(robot_move_profile *moveProfile, double targetX, double targetY, double targetZ);
00047 
00048 /***control the servo move directly,with out plan***/
00049 AUBOAPI_DLLSHARED_EXPORT int  robot_servoj(double *jointAngle, int len);
00050 
00051 /***joint move in teach mode***/
00052 AUBOAPI_DLLSHARED_EXPORT int  robot_joint_move_teach(bool dir, int jointId, int speed);
00053 
00054 /***joint step move in teach mode***/
00055 AUBOAPI_DLLSHARED_EXPORT int  robot_joint_step_move_teach(bool dir, int jointId, int speed, double jointStep);
00056 
00057 /***point move in teach mode***/
00058 AUBOAPI_DLLSHARED_EXPORT int  robot_point_move_teach(robot_coord_type coordinage, robot_moveway move_code, int speed);
00059 
00060 /***point step move in teach mode***/
00061 AUBOAPI_DLLSHARED_EXPORT int  robot_point_step_move_teach(robot_coord_type coordinage, robot_moveway move_code, int speed, double step);
00062 
00063 /***inverse kinematics***/
00064 AUBOAPI_DLLSHARED_EXPORT int  robot_ik(double targetX,  double targetY, double targetZ, double *currentJointPos, our_robot_road_point *roadPoint);
00065 
00066 /***forward kinematics***/
00067 AUBOAPI_DLLSHARED_EXPORT int  robot_fk(double *jointPos, our_robot_road_point *roadPoint);
00068 
00069 /***stop move***/
00070 AUBOAPI_DLLSHARED_EXPORT int  robot_move_stop();
00071 
00072 
00073 
00074 
00075 
00076 /***get project number***/
00077 AUBOAPI_DLLSHARED_EXPORT int get_project_count(int *count);
00078 
00079 /***get project list***/
00080 AUBOAPI_DLLSHARED_EXPORT int get_project_list(our_project_info *projects, int *len);
00081 
00082 /***load a project***/
00083 AUBOAPI_DLLSHARED_EXPORT int project_load(const our_control_project_load *projectInfo);
00084 
00085 /***control project(run,stop,pause)****/
00086 AUBOAPI_DLLSHARED_EXPORT int project_control(our_project_control controlCommand);
00087 
00088 
00089 
00090 
00091 /***get system state***/
00092 AUBOAPI_DLLSHARED_EXPORT int  get_robot_system_status(our_control_robot_system_status *robotSystemStatus);
00093 
00094 /***get joint state**/
00095 AUBOAPI_DLLSHARED_EXPORT int  get_robot_joint_status (our_control_joint_status *status, int len);
00096 
00097 /***get device info***/
00098 AUBOAPI_DLLSHARED_EXPORT int  get_robot_device_info  (RobotDeviceInfo *deviceInfo);
00099 
00100 /***get robot move state***/
00101 AUBOAPI_DLLSHARED_EXPORT int  get_robot_run_status   (our_robot_status *status);
00102 
00103 /***get robot current position***/
00104 AUBOAPI_DLLSHARED_EXPORT int  get_robot_position     (our_robot_road_point *pos);
00105 
00106 /***get robot end speed***/
00107 AUBOAPI_DLLSHARED_EXPORT int  get_robot_end_speed    (double *speed);
00108 
00109 
00110 
00111 /***set robot power***/
00112 AUBOAPI_DLLSHARED_EXPORT int set_robot_power(int value);
00113 
00114 /***set collision level***/
00115 AUBOAPI_DLLSHARED_EXPORT int set_collision_grade(int value);
00116 
00117 /***set robot mode***/
00118 AUBOAPI_DLLSHARED_EXPORT int set_robot_mode(our_control_robot_mode mode);
00119 
00120 /***get rbot mode***/
00121 AUBOAPI_DLLSHARED_EXPORT int get_robot_mode(our_control_robot_mode *mode);
00122 
00123 /***set tcp center***/
00124 AUBOAPI_DLLSHARED_EXPORT int set_robot_tcp_param (double x, double y, double z, double payload );
00125 
00126 /***get tcp center***/
00127 AUBOAPI_DLLSHARED_EXPORT int get_robot_tcp_param (double *x,double *y,double *z,double *payload);
00128 
00129 /***set brake***/
00130 AUBOAPI_DLLSHARED_EXPORT int set_robot_brake();
00131 
00132 /***release brake***/
00133 AUBOAPI_DLLSHARED_EXPORT int set_robot_brake_release();
00134 
00135 /***warning for over speed***/
00136 AUBOAPI_DLLSHARED_EXPORT int set_rverspeed_warning();
00137 
00138 /***recover from over speed waring***/
00139 AUBOAPI_DLLSHARED_EXPORT int set_overspeed_warning_recover();
00140 
00141 /***enable force control***/
00142 AUBOAPI_DLLSHARED_EXPORT int set_enable_force_control();
00143 
00144 /***disable force control***/
00145 AUBOAPI_DLLSHARED_EXPORT int set_disable_force_control();
00146 
00147 /***enable read pose function***/
00148 AUBOAPI_DLLSHARED_EXPORT int set_enable_read_pose();
00149 
00150 /***disable read pose function***/
00151 AUBOAPI_DLLSHARED_EXPORT int set_disable_read_pose();
00152 
00153 /***set fixed pose changed***/
00154 AUBOAPI_DLLSHARED_EXPORT int set_mounting_pose_changed();
00155 
00156 /***set fixed pose unchanged***/
00157 AUBOAPI_DLLSHARED_EXPORT int set_mounting_pose_unchanged();
00158 
00159 /***enable static collision detect function***/
00160 AUBOAPI_DLLSHARED_EXPORT int set_enable_static_collision_detect();
00161 
00162 /***disable static collision detect function***/
00163 AUBOAPI_DLLSHARED_EXPORT int set_disable_static_collision_detect();
00164 
00165 
00166 
00167 
00168 /***set single io status***/
00169 AUBOAPI_DLLSHARED_EXPORT int set_single_io_status( our_contorl_io_type  ioType, our_contorl_io_mode ioMode, int ioIndex, double ioValue);
00170 
00171 /***get single io status***/
00172 AUBOAPI_DLLSHARED_EXPORT int get_single_io_status( our_contorl_io_type  ioType, our_contorl_io_mode ioMode, int ioIndex, double *ioValue);
00173 
00174 /***set one or more io status***/
00175 AUBOAPI_DLLSHARED_EXPORT int set_io_status( const our_control_io_status *ioStatusArray, int len);
00176 
00177 /***get one or more io status***/
00178 AUBOAPI_DLLSHARED_EXPORT int get_io_status( our_control_io_status *ioStatusArray, int len);
00179 
00180 
00181 
00182 /***init move profile***/
00183 AUBOAPI_DLLSHARED_EXPORT void init_move_profile_for_script();
00184 
00185 /***enable scurve***/
00186 AUBOAPI_DLLSHARED_EXPORT void set_scurve(int value);
00187 
00188 /***set move relative offset***/
00189 AUBOAPI_DLLSHARED_EXPORT void set_relative_offset(double x,double y,double z);
00190 
00191 /***disable move relative offset***/
00192 AUBOAPI_DLLSHARED_EXPORT void disable_relative_offset();
00193 
00194 /***set feature(base,end)***/
00195 AUBOAPI_DLLSHARED_EXPORT void set_feature(int type);
00196 
00197 /***set user feature***/
00198 AUBOAPI_DLLSHARED_EXPORT void set_user_feature(double waypoint1[],double waypoint2[],double waypoint3[],int type);
00199 
00200 /***add waypoint for movep***/
00201 AUBOAPI_DLLSHARED_EXPORT void add_waypoint_for_moveP(const double pos[], int count);
00202 
00203 /***enable or disable block function,which mean whether wait for the move finish signal.***/
00204 AUBOAPI_DLLSHARED_EXPORT void set_enable_block(int value);
00205 
00206 /***movej for script***/
00207 AUBOAPI_DLLSHARED_EXPORT int robot_moveJ_for_script(double pos[], int count, double acc, double velc);
00208 
00209 /***movel for script***/
00210 AUBOAPI_DLLSHARED_EXPORT int robot_moveL_for_script(double pos[], int count, double acc, double velc);
00211 
00212 /***movep for script***/
00213 AUBOAPI_DLLSHARED_EXPORT int robot_moveP_for_script(double acc, double velc, double blendRadius, int trackMode);
00214 
00215 /***moveto for script***/
00216 AUBOAPI_DLLSHARED_EXPORT int robot_movelTo_for_script(double targetX, double targetY, double targetZ, double acc, double velc);
00217 
00218 }
00219 
00220 #endif // OUR_CONTROL_API_V1_H


aubo_driver
Author(s): liuxin
autogenerated on Sat Jun 8 2019 19:06:01