metaType.h
Go to the documentation of this file.
00001 #ifndef OURCONTROL_H
00002 #define OURCONTROL_H
00003 
00004 #ifndef METATYPE_H
00005 #define METATYPE_H
00006 
00007 #include <stdint.h>
00008 #include <iostream>
00009 
00010 #include <map>
00011 
00012 
00013 #define PACKED  __attribute__((__packed__))
00014 
00015 typedef unsigned char uchar;
00016 
00017 typedef struct PACKED
00018 {
00019     uint32_t sof;
00020     uint32_t len;
00021 
00022 }our_control_json_header;
00023 
00024 #define OUR_JSON_HEADERSIZE sizeof(our_control_json_header)
00025 
00026 
00027 typedef struct PACKED
00028 {
00029     uint32_t crc;
00030     uint32_t end;
00031 
00032 }our_control_json_tail;
00033 
00034 #define OUR_JSON_TAILSIZE sizeof(our_control_json_tail)
00035 
00036 typedef struct
00037 {
00038     our_control_json_header json_header;
00039     std::string     json_data;
00040     our_control_json_tail   json_tail;
00041 }our_control_json_frame;
00042 
00043 
00044 typedef struct
00045 {
00046     std::string user_name;
00047     std::string user_pwd;
00048 }our_control_login;
00049 
00050 typedef struct
00051 {
00052     std::string project_name;
00053     std::string feature_name;
00054     float relative_offset_x;
00055     float relative_offset_y;
00056     float relative_offset_z;
00057 }our_control_project_load;
00058 
00059 typedef enum
00060 {
00061     project_no_opera,
00062     project_start,
00063     project_stop,
00064     project_pause,
00065 }our_project_control;
00066 
00067 typedef struct
00068 {
00069     std::string project_name;
00070     std::string descripiton;
00071 }our_project_info;
00072 
00073 typedef enum
00074 {
00075     robot_running,
00076     robot_stop,
00077     robot_pause,
00078     robot_emergency,
00079 
00080     robot_unknown = 9
00081 }our_robot_status;
00082 
00083 typedef enum
00084 {
00085     robot_project_ready = 0,
00086     robot_project_running,
00087     robot_project_step_running,
00088     robot_project_suspend
00089 }our_project_status;
00090 
00091 typedef struct
00092 {
00093     double pos[3];       //x,y,z coodinate
00094     double ori[4];       //w,x,y,z
00095     double joint_pos[6]; //joint1~6 angle
00096 }our_robot_road_point;
00097 
00098 typedef struct
00099 {
00100     our_robot_status robot_status;
00101     our_robot_road_point pos_on_base_coord;
00102     our_robot_road_point pos_on_tool_coord;
00103     our_robot_road_point pos_on_user_coord;
00104 }our_control_robot_status;
00105 
00106 
00107 typedef enum
00108 {
00109     no_convert,
00110     base_to_user,
00111     user_to_base,
00112 }coord_convert_type;
00113 
00114 typedef struct
00115 {
00116     coord_convert_type convert_type;
00117 
00118     double tcp[3];//x,y,z tool offset;
00119 
00120     our_robot_road_point plane_points[3];
00121 
00122     //source_point
00123     our_robot_road_point source_point;
00124 
00125     //target_point
00126     our_robot_road_point target_point;
00127 
00128     bool orientation_used;
00129 
00130 }our_control_coord_convert;
00131 
00132 
00133 typedef enum {
00134     our_feature_base = 0,
00135     our_feature_end,
00136     our_feature_user
00137 }our_feature_type;
00138 
00139 
00140 typedef struct{
00141     std::string feature_name;
00142     our_robot_road_point plane[3];
00143 }our_control_feature;
00144 
00145 
00146 typedef enum
00147 {
00148     our_move_mode_j = 1,
00149     our_move_mode_l,
00150     our_move_mode_p,
00151     our_move_unknown_mode
00152 }our_move_mode_type;
00153 
00154 
00155 typedef enum
00156 {
00157     arc = 0,
00158     circular,
00159     cartesian_cubicspline,
00160     cartesian_ubsplineintp,
00161     cartesian_movep,
00162     jiont_cubicspline = 20,
00163     joint_ubsplineintp,
00164     track_mode_count = 6
00165 
00166 }our_move_track_type;
00167 
00168 typedef struct{
00169     double max_velc_jc;
00170     double max_acc_jc;
00171     bool scurve;
00172     our_move_mode_type move_mode;
00173     our_move_track_type move_track;
00174     bool tool_track;
00175     bool relative_move;
00176     our_feature_type user_coord;
00177     float relative_position[3];
00178     float tcp[3];
00179     double blend_radius;
00180     our_control_feature feature;
00181 
00182 }robot_move_profile;
00183 
00184 typedef enum{
00185     move_x,
00186     move_y,
00187     move_z,
00188     rotate_x,
00189     rotate_y,
00190     rotate_z
00191 }robot_moveway;
00192 
00193 typedef enum{
00194     real_coord = 0x01,
00195     word_coord = 0x02,
00196     base_coord = 0x03
00197 }robot_coord_type;
00198 
00199 typedef struct{
00200     robot_coord_type coordinage;
00201     robot_moveway move_code;
00202     int speed;
00203     double move_step;
00204 }robot_teach_point_move;
00205 
00206 typedef struct{
00207     bool dir;
00208     int joint_id;
00209     int speed;
00210     double joint_step; //default=1000
00211 }robot_teach_joint_move;
00212 
00213 
00214 
00215 typedef enum
00216 {
00217     our_control_ok,
00218     our_control_json_error
00219 }our_control_command_result;
00220 
00221 
00222 
00223 typedef struct
00224 {
00225     int len;
00226     uchar *buf;
00227 }our_com_frame;
00228 
00229 
00233 typedef enum{
00234     robot_event_current_pos,
00235     robot_event_soft_emergency,
00236     robot_event_collision,
00237     robot_event_over_speed,
00238     robot_event_force_control,
00239     robot_event_joint_error,
00240     robot_event_at_track_target_pos,
00241     robot_event_mounting_pose_changed,
00242     robot_event_project_status_changed,
00243 
00244     //event count
00245     robot_event_count,
00246 
00247     //unknown event
00248     robot_event_unknown
00249 }our_control_event;
00250 
00251 typedef struct
00252 {
00253     our_control_event event_id;
00254     std::string desc;
00255 }our_event;
00256 
00257 typedef struct{
00258     int  type;
00259     int  code;
00260     std::string message;
00261 }our_control_event_msg;
00262 
00263 
00264 typedef enum
00265 {
00266     io_bus_type_plc,
00267     io_bus_type_tool,
00268     io_bus_type_board,
00269     io_bus_type_modbus
00270 }our_contorl_io_type;
00271 
00272 typedef enum
00273 {
00274     io_mode_do,
00275     io_mode_di,
00276     io_mode_ao,
00277     io_mode_ai
00278 }our_contorl_io_mode;
00279 
00280 typedef struct
00281 {
00282     our_contorl_io_type io_type;
00283     our_contorl_io_mode io_mode;
00284     int io_index;
00285 }our_contorl_io_config;
00286 
00287 typedef struct
00288 {
00289     our_contorl_io_type  io_type;
00290     our_contorl_io_mode  io_mode;
00291     int      io_index;
00292     double   io_value;
00293 }our_control_io_status;
00294 
00295 typedef struct
00296 {
00297     int     joint_id;
00298     float   joint_voltage;
00299     float   joint_current;
00300     float   joint_temperature;
00301 }our_control_joint_status;
00302 
00303 typedef struct
00304 {
00305     //硬件版本 (u16)(100)
00306     unsigned short hw_version;
00307     //固件版本 (u16)((15<<9)|(5<<5)|(13)) 表示:2015年5月13日
00308     unsigned short sw_version;
00309 }our_control_joint_version;
00310 
00311 typedef struct
00312 {
00313     //设备型号、芯片型号:上位机主站:0x01  接口板0x02
00314     unsigned char type;
00315     //设备版本号,V1.0
00316     std::string revision;
00317     //厂家ID,"OUR "的ASCII码0x4F 55 52 00
00318     std::string manu_id;
00319     //机械臂类型
00320     std::string joint_type;
00321     //机械臂关节及工具端信息
00322     our_control_joint_version joint_ver[7];
00323     //设备描述字符串以0x00结束
00324     std::string desc;
00325 
00326 }our_control_robot_device_info;
00327 
00328 typedef struct
00329 {
00330     //机械臂48V电源当前电流
00331     float power_current;
00332     //机械臂48V电源当前电压
00333     float power_voltage;
00334     //机械臂48V电源状态(开、关)
00335     bool  power_status;
00336     //控制箱温度
00337     char  controller_temp;
00338     //控制箱湿度
00339     uchar controller_humidity;
00340     //远程关机信号
00341     bool  remote_halt;
00342     //机械臂软急停
00343     bool  soft_emergency;
00344     //远程急停信号
00345     bool  remote_emergency;
00346     //碰撞检测位
00347     bool  robot_collision;
00348     //机械臂进入力控模式标志位
00349     bool  force_control_mode;
00350     //刹车状态
00351     bool brake_stuats;
00352     //末端速度
00353     float end_speed;
00354     //最大加速度
00355     int max_acc;
00356     //位姿读取使能位
00357     bool enble_read_pose;
00358     //安装位置状态
00359     bool mounting_pose_changed;
00360     //磁编码器错误状态
00361     bool encoder_error_status;
00362 }our_control_robot_system_status;
00363 
00364 typedef std::map<int, our_com_frame*> OUR_CLENT_MAP;
00365 
00366 
00367 typedef struct
00368 {
00369     //TCP距离中心点距离X(单位,毫米)
00370     float x;
00371     //TCP距离中心点距离Y(单位,毫米)
00372     float y;
00373     //TCP距离中心点距离Z(单位,毫米)
00374     float z;
00375     //TCP负载重量(单位,公斤)
00376     float payload;
00377 
00378 }our_control_tpc_center;
00379 
00380 typedef struct
00381 {
00382     our_control_tpc_center runtime;  //运行时负载
00383     our_control_tpc_center manual;   //手动时负载
00384 }our_control_tcp_center_param;
00385 
00386 typedef enum{
00387     robot_release                   = 0, //释放刹车
00388     robot_brake                     = 1, //刹车
00389     overspeed_warning               = 2, //拖动示教速度过快报警
00390     overspeed_recover               = 3, //解除拖动过速报警
00391     disable_force_control           = 4, //失能力控
00392     enable_force_control            = 5, //使能力控
00393     orpe_open                       = 6, //打开上位机软件
00394     erpe_close                      = 7, //关闭上位机软件
00395     enable_read_pose                = 8, //打开读取位姿
00396     disable_read_pose               = 9, //关闭读取位姿
00397     mounting_pose_changed           = 10,//安装位置已改变
00398     mounting_pose_unchanged         = 11,//安装位置未改变
00399     enable_static_collision_detect  = 12,//打开静止碰撞检测
00400     disable_static_collision_detect = 13 //关闭静止碰撞检测
00401 }our_control_robot_command;
00402 
00403 typedef enum {
00404     no_error      = 0, //无错误
00405     over_voltage  = 1, //过压
00406     under_voltage = 2, //欠压
00407     over_temp     = 3, //过温
00408     canbus_error  = 4  //CAN总线错误
00409 }our_control_robot_tool_status;
00410 
00411 typedef struct
00412 {
00413     unsigned short current1;
00414     unsigned short current2;
00415     unsigned short current3;
00416     unsigned short current4;
00417 }our_control_joint_collision_current;
00418 
00419 typedef struct
00420 {
00421     our_control_joint_collision_current joint1;
00422     our_control_joint_collision_current joint2;
00423     our_control_joint_collision_current joint3;
00424     our_control_joint_collision_current joint4;
00425     our_control_joint_collision_current joint5;
00426     our_control_joint_collision_current joint6;
00427     uchar collision_class;
00428 
00429 }our_control_robot_collision_param;
00430 
00431 
00432 typedef enum{
00433     robot_mode_simulator, //机械臂仿真模式
00434     robot_mode_real,       //机械臂真实模式
00435     robot_mode_unknow
00436 }our_control_robot_mode;
00437 
00438 
00439 
00440 typedef enum{
00441     state_ready,                  //ready
00442     state_connect_interfaceboard, //正在链接接口板
00443     state_init_ok,                //初始化成功
00444     state_init_failed,            //链接接口板失败,请检查接口板RJ45链接线是否链接正常
00445 }our_control_init_status;
00446 
00447 
00448 
00449 //事件推送  函数指针类型
00450 typedef void (*EventPushCallback)(our_control_event, our_control_event_msg);
00451 
00452 //实时路点事件  函数指针类型
00453 typedef void (*RealTimeRoadPointEventCallback)(our_robot_road_point roadPoint, float endSpeed);
00454 
00455 
00456 #define RESPONSE_COMMAND     "response_command"
00457 #define RESPONSE_ERROR_CODE  "error_code"
00458 #define RESPONSE_ERROR_MSG   "error_msg"
00459 
00460 #define TCP_MESSAGE_SOF_BYTE 4                //MESSAGE_SOF
00461 #define TCP_MESSAGE_DATA_LEN_BYTE 4           //MESSAGE_DATA_LEN
00462 #define TCP_MESSAGE_DATA_MAX_BYTE (1024*1024) //MESSAGE_DATA
00463 #define TCP_MESSAGE_CRC_BYTE 4                //CRC
00464 #define TCP_MESSAGE_END_BYTE 4                //MESSAGE_END
00465 #define TCP_MESSAGE_PACKAGE_BYTE   (TCP_MESSAGE_SOF_BYTE+TCP_MESSAGE_DATA_LEN_BYTE+TCP_MESSAGE_DATA_MAX_BYTE+TCP_MESSAGE_CRC_BYTE+TCP_MESSAGE_END_BYTE)
00466 
00467 #define TCP_MESSAGE_BYTE (4*1024)
00468 
00469 
00470 
00471 
00472 
00473 /***机械臂路点属性之关节角形式****/
00474 typedef struct
00475 {
00476     double joint[6];
00477 
00478 }RobotRoadPointJoint;
00479 
00480 
00481 /***机械臂路点属性之坐标形式***/
00482 typedef struct
00483 {
00484     double x;
00485     double y;
00486     double z;
00487 }RobotRoadPointPosition;
00488 
00489 
00490 /***机械臂路点属性之姿态形式***/
00491 typedef struct
00492 {
00493     double w;
00494     double x;
00495     double y;
00496     double z;
00497 }RobotRoadPointPose;
00498 
00499 
00500 /***机械臂路点***/
00501 typedef struct
00502 {
00503     RobotRoadPointJoint    roadPointJoint;
00504     RobotRoadPointPosition roadPointPosition;
00505     RobotRoadPointPose     roadPointPose;
00506 }RobotRoadPoint;
00507 
00508 
00509 /***硬件和固件版本***/
00510 typedef struct PACKED
00511 {
00512     unsigned short hw_version;     //硬件版本 (u16)(100)
00513     unsigned short sw_version;     //固件版本 (u16)((15<<9)|(5<<5)|(13)) 表示:2015年5月13日
00514 }RobotJointVer;
00515 
00516 
00517 /***设备信息***/
00518 typedef struct PACKED
00519 {
00520     unsigned char type;                      //设备型号、芯片型号:上位机主站:0x01  接口板0x02
00521     char revision[16];               //设备版本号,V1.0
00522     char manu_id[32];                //厂家ID,"OUR "的ASCII码0x4F 55 52 00
00523     char joint_type[16];             //机械臂类型
00524     RobotJointVer joint_ver[7];  //机械臂关节及工具端信息
00525     char desc[64];                   //设备描述字符串以0x00结束
00526 
00527 }RobotDeviceInfo;
00528 
00529 
00530 
00531 #endif // METATYPE_H
00532 
00533 #endif


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