motoman_direct_message.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *      * Redistributions of source code must retain the above copyright
00011  *      notice, this list of conditions and the following disclaimer.
00012  *      * Redistributions in binary form must reproduce the above copyright
00013  *      notice, this list of conditions and the following disclaimer in the
00014  *      documentation and/or other materials provided with the distribution.
00015  *      * Neither the name of the Southwest Research Institute, nor the names
00016  *      of its contributors may be used to endorse or promote products derived
00017  *      from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #ifndef MOTOMAN_DIRECT_MESSAGE_H
00033 #define MOTOMAN_DIRECT_MESSAGE_H
00034 
00035 #define ROS_MAX_JOINT 10
00036 
00037 
00038 //----------------
00039 // Prefix Section
00040 //----------------
00041 
00042 typedef struct
00043 {
00044         int length;
00045 } SmPrefix;
00046 
00047 //----------------
00048 // Header Section
00049 //----------------
00050 
00051 typedef enum
00052 {
00053         ROS_MSG_ROBOT_STATUS = 13,
00054         ROS_MSG_JOINT_TRAJ_PT_FULL = 14,
00055         ROS_MSG_JOINT_FEEDBACK = 15,
00056         ROS_MSG_MOTO_MOTION_CTRL = 2001,
00057         ROS_MSG_MOTO_MOTION_REPLY = 2002        
00058 } SmMsgType;
00059 
00060 
00061 typedef enum
00062 {
00063     ROS_COMM_INVALID = 0,
00064         ROS_COMM_TOPIC = 1,
00065         ROS_COMM_SERVICE_RESQUEST = 2,
00066         ROS_COMM_SERVICE_REPLY = 3
00067 } SmCommType;
00068 
00069 
00070 typedef enum 
00071 {
00072         ROS_REPLY_INVALID = 0,
00073         ROS_REPLY_SUCCESS = 1,
00074         ROS_REPLY_FAILURE = 2,
00075 } SmReplyType;
00076 
00077 
00078 typedef struct
00079 {
00080         SmMsgType msgType;
00081         SmCommType commType;
00082         SmReplyType replyType;
00083 } SmHeader;
00084 
00085 //--------------
00086 // Body Section
00087 //--------------
00088 
00089 typedef struct                                  // ROS_MSG_ROBOT_STATUS = 13
00090 {
00091         int drives_powered;                     // Servo Power: -1=Unknown, 1=ON, 0=OFF
00092         int e_stopped;                          // Controller E-Stop state: -1=Unknown, 1=True(ON), 0=False(OFF)
00093         int error_code;                         // Alarm code
00094         int in_error;                           // Is there an alarm:   -1=Unknown, 1=True, 0=False 
00095         int in_motion;                          // Is currently executing a motion command:  -1=Unknown, 1=True, 0=False 
00096         int mode;                                       // Controller/Pendant mode: -1=Unknown, 1=Manual(TEACH), 2=Auto(PLAY)
00097         int motion_possible;            // Is the controller ready to receive motion: -1=Unknown, 1=ENABLED, 0=DISABLED 
00098 } SmBodyRobotStatus;    
00099 
00100 
00101 typedef struct                                  // ROS_MSG_JOINT_TRAJ_PT_FULL = 14
00102 {
00103         int groupNo;                            // Robot/group ID;  0 = 1st robot 
00104         int sequence;                           // Index of point in trajectory; 0 = Initial trajectory point, which should match the robot current position.
00105         int validFields;                        // Bit-mask indicating which “optional” fields are filled with data. 1=time, 2=position, 4=velocity, 8=acceleration
00106         float time;                                     // Timestamp associated with this trajectory point; Units: in seconds 
00107         float pos[ROS_MAX_JOINT];       // Desired joint positions in radian.  Base to Tool joint order  
00108         float vel[ROS_MAX_JOINT];       // Desired joint velocities in radian/sec.  
00109         float acc[ROS_MAX_JOINT];       // Desired joint accelerations in radian/sec^2.
00110 } SmBodyJointTrajPtFull;        
00111 
00112 
00113 typedef struct                                  // ROS_MSG_JOINT_FEEDBACK = 15
00114 {
00115         int groupNo;                            // Robot/group ID;  0 = 1st robot 
00116         int validFields;                        // Bit-mask indicating which “optional” fields are filled with data. 1=time, 2=position, 4=velocity, 8=acceleration
00117         float time;                                     // Timestamp associated with this trajectory point; Units: in seconds 
00118         float pos[ROS_MAX_JOINT];       // Desired joint positions in radian.  Base to Tool joint order  
00119         float vel[ROS_MAX_JOINT];       // Desired joint velocities in radian/sec.  
00120         float acc[ROS_MAX_JOINT];       // Desired joint accelerations in radian/sec^2.
00121 } SmBodyJointFeedback; 
00122 
00123 
00124 typedef enum 
00125 {
00126         ROS_CMD_CHECK_MOTION_READY = 200101,
00127         ROS_CMD_CHECK_QUEUE_CNT = 200102,
00128         ROS_CMD_STOP_MOTION = 200111,
00129         ROS_CMD_START_TRAJ_MODE = 200121,
00130         ROS_CMD_STOP_TRAJ_MODE = 200122,
00131         ROS_CMD_DISCONNECT = 200130
00132 } SmCommandType;
00133 
00134 
00135 typedef struct                                  // ROS_MSG_MOTO_MOTION_CTRL = 2011
00136 {
00137         int groupNo;                            // Robot/group ID;  0 = 1st robot 
00138         int sequence;                           // Optional message tracking number that will be echoed back in the response.
00139         SmCommandType command;          // Desired command
00140         float data[ROS_MAX_JOINT];      // Command data - for future use  
00141 } SmBodyMotoMotionCtrl; 
00142 
00143 
00144 typedef enum 
00145 {
00146         ROS_RESULT_SUCCESS = 0,
00147         ROS_RESULT_TRUE = 0,
00148         ROS_RESULT_BUSY = 1,
00149         ROS_RESULT_FAILURE = 2,
00150         ROS_RESULT_FALSE = 2,
00151         ROS_RESULT_INVALID = 3,
00152         ROS_RESULT_ALARM = 4,
00153         ROS_RESULT_NOT_READY = 5,
00154         ROS_RESULT_MP_FAILURE = 6
00155 } SmResultType;
00156 
00157 typedef enum 
00158 {
00159         ROS_RESULT_INVALID_UNSPECIFIED = 3000,
00160         ROS_RESULT_INVALID_MSGSIZE,
00161         ROS_RESULT_INVALID_MSGHEADER,
00162         ROS_RESULT_INVALID_MSGTYPE,
00163         ROS_RESULT_INVALID_GROUPNO,
00164         ROS_RESULT_INVALID_SEQUENCE,
00165         ROS_RESULT_INVALID_COMMAND,
00166         ROS_RESULT_INVALID_DATA = 3010,
00167         ROS_RESULT_INVALID_DATA_START_POS,
00168         ROS_RESULT_INVALID_DATA_POSITION,
00169         ROS_RESULT_INVALID_DATA_SPEED,
00170         ROS_RESULT_INVALID_DATA_ACCEL,  
00171         ROS_RESULT_INVALID_DATA_INSUFFICIENT
00172 } SmInvalidSubCode;
00173 
00174 
00175 typedef enum
00176 {
00177         ROS_RESULT_NOT_READY_UNSPECIFIED = 5000,
00178         ROS_RESULT_NOT_READY_ALARM,
00179         ROS_RESULT_NOT_READY_ERROR,
00180         ROS_RESULT_NOT_READY_ESTOP,
00181         ROS_RESULT_NOT_READY_NOT_PLAY,
00182         ROS_RESULT_NOT_READY_NOT_REMOTE,
00183         ROS_RESULT_NOT_READY_SERVO_OFF,
00184         ROS_RESULT_NOT_READY_HOLD,
00185         ROS_RESULT_NOT_READY_NOT_STARTED,
00186         ROS_RESULT_NOT_READY_WAITING_ROS,
00187         ROS_RESULT_NOT_READY_SKILLSEND
00188 } SmNotReadySubcode;
00189         
00190 
00191 typedef struct                                  // ROS_MSG_MOTO_MOTION_REPLY = 2012
00192 {
00193         int groupNo;                            // Robot/group ID;  0 = 1st robot 
00194         int sequence;                           // Optional message tracking number that will be echoed back in the response.
00195         int command;                            // Reference to the received message command or type
00196         SmResultType result;            // High level result code
00197         int subcode;                            // More detailed result code (optional)
00198         float data[ROS_MAX_JOINT];      // Reply data - for future use 
00199 } SmBodyMotoMotionReply; 
00200 
00201 
00202 typedef union
00203 {
00204         SmBodyRobotStatus robotStatus;
00205         SmBodyJointTrajPtFull jointTrajData;
00206         SmBodyJointFeedback     jointFeedback;
00207         SmBodyMotoMotionCtrl motionCtrl;
00208         SmBodyMotoMotionReply motionReply;
00209 } SmBody;
00210 
00211 
00212 //-------------------
00213 // SimpleMsg Section
00214 //-------------------
00215 struct _SimpleMsg
00216 {
00217         SmPrefix prefix;
00218         SmHeader header;
00219         SmBody body;
00220 }  __attribute__((__packed__));
00221 typedef struct _SimpleMsg       SimpleMsg;
00222 
00223 #endif


fs100_motoman
Author(s): Asger Winther-Jørgensen (Technical Univeristy of Denmark)
autogenerated on Fri Aug 28 2015 10:42:16