Classes | Defines | Typedefs | Enumerations
metaType.h File Reference
#include <stdint.h>
#include <iostream>
#include <map>
Include dependency graph for metaType.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  our_com_frame
struct  our_contorl_io_config
struct  our_control_coord_convert
struct  our_control_event_msg
struct  our_control_feature
struct  our_control_io_status
struct  our_control_joint_collision_current
struct  our_control_joint_status
struct  our_control_joint_version
struct  our_control_json_frame
struct  our_control_login
struct  our_control_project_load
struct  our_control_robot_collision_param
struct  our_control_robot_device_info
struct  our_control_robot_status
struct  our_control_robot_system_status
struct  our_control_tcp_center_param
struct  our_control_tpc_center
struct  our_event
struct  our_project_info
struct  our_robot_road_point
struct  PACKED
struct  PACKED
struct  PACKED
struct  PACKED
struct  robot_move_profile
struct  robot_teach_joint_move
struct  robot_teach_point_move
struct  RobotRoadPoint
struct  RobotRoadPointJoint
struct  RobotRoadPointPose
struct  RobotRoadPointPosition

Defines

#define METATYPE_H
#define OUR_JSON_HEADERSIZE   sizeof(our_control_json_header)
#define OUR_JSON_TAILSIZE   sizeof(our_control_json_tail)
#define PACKED   __attribute__((__packed__))
#define RESPONSE_COMMAND   "response_command"
#define RESPONSE_ERROR_CODE   "error_code"
#define RESPONSE_ERROR_MSG   "error_msg"
#define TCP_MESSAGE_BYTE   (4*1024)
#define TCP_MESSAGE_CRC_BYTE   4
#define TCP_MESSAGE_DATA_LEN_BYTE   4
#define TCP_MESSAGE_DATA_MAX_BYTE   (1024*1024)
#define TCP_MESSAGE_END_BYTE   4
#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)
#define TCP_MESSAGE_SOF_BYTE   4

Typedefs

typedef void(* EventPushCallback )(our_control_event, our_control_event_msg)
typedef std::map< int,
our_com_frame * > 
OUR_CLENT_MAP
typedef struct PACKED our_control_json_header
typedef struct PACKED our_control_json_tail
typedef void(* RealTimeRoadPointEventCallback )(our_robot_road_point roadPoint, float endSpeed)
typedef struct PACKED RobotDeviceInfo
typedef struct PACKED RobotJointVer
typedef unsigned char uchar

Enumerations

enum  coord_convert_type { no_convert, base_to_user, user_to_base }
enum  our_contorl_io_mode { io_mode_do, io_mode_di, io_mode_ao, io_mode_ai }
enum  our_contorl_io_type { io_bus_type_plc, io_bus_type_tool, io_bus_type_board, io_bus_type_modbus }
enum  our_control_command_result { our_control_ok, our_control_json_error }
enum  our_control_event {
  robot_event_current_pos, robot_event_soft_emergency, robot_event_collision, robot_event_over_speed,
  robot_event_force_control, robot_event_joint_error, robot_event_at_track_target_pos, robot_event_mounting_pose_changed,
  robot_event_project_status_changed, robot_event_count, robot_event_unknown
}
enum  our_control_init_status { state_ready, state_connect_interfaceboard, state_init_ok, state_init_failed }
enum  our_control_robot_command {
  robot_release = 0, robot_brake = 1, overspeed_warning = 2, overspeed_recover = 3,
  disable_force_control = 4, enable_force_control = 5, orpe_open = 6, erpe_close = 7,
  enable_read_pose = 8, disable_read_pose = 9, mounting_pose_changed = 10, mounting_pose_unchanged = 11,
  enable_static_collision_detect = 12, disable_static_collision_detect = 13
}
enum  our_control_robot_mode { robot_mode_simulator, robot_mode_real, robot_mode_unknow }
enum  our_control_robot_tool_status {
  no_error = 0, over_voltage = 1, under_voltage = 2, over_temp = 3,
  canbus_error = 4
}
enum  our_feature_type { our_feature_base = 0, our_feature_end, our_feature_user }
enum  our_move_mode_type { our_move_mode_j = 1, our_move_mode_l, our_move_mode_p, our_move_unknown_mode }
enum  our_move_track_type {
  arc = 0, circular, cartesian_cubicspline, cartesian_ubsplineintp,
  cartesian_movep, jiont_cubicspline = 20, joint_ubsplineintp, track_mode_count = 6
}
enum  our_project_control { project_no_opera, project_start, project_stop, project_pause }
enum  our_project_status { robot_project_ready = 0, robot_project_running, robot_project_step_running, robot_project_suspend }
enum  our_robot_status {
  robot_running, robot_stop, robot_pause, robot_emergency,
  robot_unknown = 9
}
enum  robot_coord_type { real_coord = 0x01, word_coord = 0x02, base_coord = 0x03 }
enum  robot_moveway {
  move_x, move_y, move_z, rotate_x,
  rotate_y, rotate_z
}

Define Documentation

#define METATYPE_H

Definition at line 5 of file metaType.h.

Definition at line 24 of file metaType.h.

Definition at line 34 of file metaType.h.

#define PACKED   __attribute__((__packed__))

Definition at line 13 of file metaType.h.

#define RESPONSE_COMMAND   "response_command"

Definition at line 456 of file metaType.h.

#define RESPONSE_ERROR_CODE   "error_code"

Definition at line 457 of file metaType.h.

#define RESPONSE_ERROR_MSG   "error_msg"

Definition at line 458 of file metaType.h.

#define TCP_MESSAGE_BYTE   (4*1024)

Definition at line 467 of file metaType.h.

#define TCP_MESSAGE_CRC_BYTE   4

Definition at line 463 of file metaType.h.

#define TCP_MESSAGE_DATA_LEN_BYTE   4

Definition at line 461 of file metaType.h.

#define TCP_MESSAGE_DATA_MAX_BYTE   (1024*1024)

Definition at line 462 of file metaType.h.

#define TCP_MESSAGE_END_BYTE   4

Definition at line 464 of file metaType.h.

Definition at line 465 of file metaType.h.

#define TCP_MESSAGE_SOF_BYTE   4

Definition at line 460 of file metaType.h.


Typedef Documentation

Definition at line 450 of file metaType.h.

typedef std::map<int, our_com_frame*> OUR_CLENT_MAP

Definition at line 364 of file metaType.h.

typedef struct PACKED our_control_json_tail
typedef void(* RealTimeRoadPointEventCallback)(our_robot_road_point roadPoint, float endSpeed)

Definition at line 453 of file metaType.h.

typedef struct PACKED RobotDeviceInfo
typedef struct PACKED RobotJointVer
typedef unsigned char uchar

Definition at line 15 of file metaType.h.


Enumeration Type Documentation

Enumerator:
no_convert 
base_to_user 
user_to_base 

Definition at line 107 of file metaType.h.

Enumerator:
io_mode_do 
io_mode_di 
io_mode_ao 
io_mode_ai 

Definition at line 272 of file metaType.h.

Enumerator:
io_bus_type_plc 
io_bus_type_tool 
io_bus_type_board 
io_bus_type_modbus 

Definition at line 264 of file metaType.h.

Enumerator:
our_control_ok 
our_control_json_error 

Definition at line 215 of file metaType.h.

event define

Enumerator:
robot_event_current_pos 
robot_event_soft_emergency 
robot_event_collision 
robot_event_over_speed 
robot_event_force_control 
robot_event_joint_error 
robot_event_at_track_target_pos 
robot_event_mounting_pose_changed 
robot_event_project_status_changed 
robot_event_count 
robot_event_unknown 

Definition at line 233 of file metaType.h.

Enumerator:
state_ready 
state_connect_interfaceboard 
state_init_ok 
state_init_failed 

Definition at line 440 of file metaType.h.

Enumerator:
robot_release 
robot_brake 
overspeed_warning 
overspeed_recover 
disable_force_control 
enable_force_control 
orpe_open 
erpe_close 
enable_read_pose 
disable_read_pose 
mounting_pose_changed 
mounting_pose_unchanged 
enable_static_collision_detect 
disable_static_collision_detect 

Definition at line 386 of file metaType.h.

Enumerator:
robot_mode_simulator 
robot_mode_real 
robot_mode_unknow 

Definition at line 432 of file metaType.h.

Enumerator:
no_error 
over_voltage 
under_voltage 
over_temp 
canbus_error 

Definition at line 403 of file metaType.h.

Enumerator:
our_feature_base 
our_feature_end 
our_feature_user 

Definition at line 133 of file metaType.h.

Enumerator:
our_move_mode_j 
our_move_mode_l 
our_move_mode_p 
our_move_unknown_mode 

Definition at line 146 of file metaType.h.

Enumerator:
arc 
circular 
cartesian_cubicspline 
cartesian_ubsplineintp 
cartesian_movep 
jiont_cubicspline 
joint_ubsplineintp 
track_mode_count 

Definition at line 155 of file metaType.h.

Enumerator:
project_no_opera 
project_start 
project_stop 
project_pause 

Definition at line 59 of file metaType.h.

Enumerator:
robot_project_ready 
robot_project_running 
robot_project_step_running 
robot_project_suspend 

Definition at line 83 of file metaType.h.

Enumerator:
robot_running 
robot_stop 
robot_pause 
robot_emergency 
robot_unknown 

Definition at line 73 of file metaType.h.

Enumerator:
real_coord 
word_coord 
base_coord 

Definition at line 193 of file metaType.h.

Enumerator:
move_x 
move_y 
move_z 
rotate_x 
rotate_y 
rotate_z 

Definition at line 184 of file metaType.h.



aubo_driver
Author(s): liuxin
autogenerated on Wed Sep 6 2017 03:06:41