SimpleMessage.h
Go to the documentation of this file.
1 // SimpleMessage.h
2 //
3 /*
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (c) 2013, Yaskawa America, Inc.
7 * All rights reserved.
8 *
9 * Redistribution and use in binary form, with or without modification,
10 * is permitted provided that the following conditions are met:
11 *
12 * * Redistributions in binary form must reproduce the above copyright
13 * notice, this list of conditions and the following disclaimer in the
14 * documentation and/or other materials provided with the distribution.
15 * * Neither the name of the Yaskawa America, Inc., nor the names
16 * of its contributors may be used to endorse or promote products derived
17 * from this software without specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 */
31 
32 #ifndef SIMPLE_MSG_H
33 #define SIMPLE_MSG_H
34 
35 #define ROS_MAX_JOINT 10
36 #define MOT_MAX_GR 4
37 
38 
39 //----------------
40 // Prefix Section
41 //----------------
42 
43 typedef struct
44 {
45  int length;
46 } SmPrefix;
47 
48 //----------------
49 // Header Section
50 //----------------
51 
52 typedef enum
53 {
57 
60 
63 
75 
79 
81 } SmMsgType;
82 
83 
84 typedef enum
85 {
90 } SmCommType;
91 
92 
93 typedef enum
94 {
98 } SmReplyType;
99 
100 
101 typedef enum
102 {
106  ROS_CMD_START_SERVOS = 200112, // starts the servo motors
107  ROS_CMD_STOP_SERVOS = 200113, // stops the servo motors and motion
108  ROS_CMD_RESET_ALARM = 200114, // clears the error in the current controller
112 } SmCommandType;
113 
114 
115 typedef enum
116 {
126 } SmResultType;
127 
128 
129 typedef enum
130 {
147 
148 
149 typedef enum
150 {
164 
165 
166 struct _SmHeader
167 {
171 } __attribute__((__packed__));
172 typedef struct _SmHeader SmHeader;
173 
174 typedef enum
175 {
181 
182 //--------------
183 // Body Section
184 //--------------
185 
186 struct _SmBodyRobotStatus // ROS_MSG_ROBOT_STATUS = 13
187 {
188  int drives_powered; // Servo Power: -1=Unknown, 1=ON, 0=OFF
189  int e_stopped; // Controller E-Stop state: -1=Unknown, 1=True(ON), 0=False(OFF)
190  int error_code; // Alarm code
191  int in_error; // Is there an alarm: -1=Unknown, 1=True, 0=False
192  int in_motion; // Is currently executing a motion command: -1=Unknown, 1=True, 0=False
193  int mode; // Controller/Pendant mode: -1=Unknown, 1=Manual(TEACH), 2=Auto(PLAY)
194  int motion_possible; // Is the controller ready to receive motion: -1=Unknown, 1=ENABLED, 0=DISABLED
195 } __attribute__((__packed__));
197 
198 struct _SmBodyJointTrajPtFull // ROS_MSG_JOINT_TRAJ_PT_FULL = 14
199 {
200  int groupNo; // Robot/group ID; 0 = 1st robot
201  int sequence; // Index of point in trajectory; 0 = Initial trajectory point, which should match the robot current position.
202  FlagsValidFields validFields; // Bit-mask indicating which “optional” fields are filled with data. 1=time, 2=position, 4=velocity, 8=acceleration
203  float time; // Timestamp associated with this trajectory point; Units: in seconds
204  float pos[ROS_MAX_JOINT]; // Desired joint positions in radian. Base to Tool joint order
205  float vel[ROS_MAX_JOINT]; // Desired joint velocities in radian/sec.
206  float acc[ROS_MAX_JOINT]; // Desired joint accelerations in radian/sec^2.
207 } __attribute__((__packed__));
209 
210 struct _SmBodyJointFeedback // ROS_MSG_JOINT_FEEDBACK = 15
211 {
212  int groupNo; // Robot/group ID; 0 = 1st robot
213  FlagsValidFields validFields; // Bit-mask indicating which “optional” fields are filled with data. 1=time, 2=position, 4=velocity, 8=acceleration
214  float time; // Timestamp associated with this trajectory point; Units: in seconds
215  float pos[ROS_MAX_JOINT]; // Feedback joint positions in radian. Base to Tool joint order
216  float vel[ROS_MAX_JOINT]; // Feedback joint velocities in radian/sec.
217  float acc[ROS_MAX_JOINT]; // Feedback joint accelerations in radian/sec^2.
218 } __attribute__((__packed__));
220 
221 
222 struct _SmBodyMotoMotionCtrl // ROS_MSG_MOTO_MOTION_CTRL = 2001
223 {
224  int groupNo; // Robot/group ID; 0 = 1st robot
225  int sequence; // Optional message tracking number that will be echoed back in the response.
226  SmCommandType command; // Desired command
227  float data[ROS_MAX_JOINT]; // Command data - for future use
228 } __attribute__((__packed__));
230 
231 
232 struct _SmBodyMotoMotionReply // ROS_MSG_MOTO_MOTION_REPLY = 2002
233 {
234  int groupNo; // Robot/group ID; 0 = 1st robot
235  int sequence; // Optional message tracking number that will be echoed back in the response.
236  int command; // Reference to the received message command or type
237  SmResultType result; // High level result code
238  int subcode; // More detailed result code (optional)
239  float data[ROS_MAX_JOINT]; // Reply data - for future use
240 } __attribute__((__packed__));
242 
244 {
245  int groupNo; // Robot/group ID; 0 = 1st robot
246  FlagsValidFields validFields; // Bit-mask indicating which “optional” fields are filled with data. 1=time, 2=position, 4=velocity, 8=acceleration
247  float time; // Timestamp associated with this trajectory point; Units: in seconds
248  float pos[ROS_MAX_JOINT]; // Desired joint positions in radian. Base to Tool joint order
249  float vel[ROS_MAX_JOINT]; // Desired joint velocities in radian/sec.
250  float acc[ROS_MAX_JOINT]; // Desired joint accelerations in radian/sec^2.
251 } __attribute__((__packed__));
253 
255 {
257  int sequence;
259 } __attribute__((__packed__));
261 
262 
264 {
267 } __attribute__((__packed__));
269 
271 {
272  int groupNo; // Robot/group ID; 0 = 1st robot
273  int tool; // Tool no for the selected group
274  int sequence; // Optional message tracking number that will be echoed back in the response.
275 } __attribute__((__packed__));
277 
278 //--------------
279 // IO Commands
280 //--------------
281 
282 typedef enum
283 {
285  IO_RESULT_READ_ADDRESS_INVALID = 1001, //The ioAddress cannot be read on this controller
286  IO_RESULT_WRITE_ADDRESS_INVALID, //The ioAddress cannot be written to on this controller
287  IO_RESULT_WRITE_VALUE_INVALID, //The value supplied is not a valid value for the addressed IO element
288  IO_RESULT_READ_API_ERROR, //mpReadIO return -1
289  IO_RESULT_WRITE_API_ERROR //mpWriteIO returned -1
290 } IoResultCodes;
291 
293 {
294  UINT32 ioAddress;
295 } __attribute__((__packed__));
297 
299 {
300  UINT32 value;
301  IoResultCodes resultCode;
302 } __attribute__((__packed__));
304 
306 {
307  UINT32 ioAddress;
308  UINT32 ioValue;
309 } __attribute__((__packed__));
311 
313 {
314  IoResultCodes resultCode;
315 } __attribute__((__packed__));
317 
319 {
320  UINT32 ioAddress; //Group address. Example: '1001' will read OG#1 (Bits 10010 through 10017)
321 } __attribute__((__packed__));
323 
325 {
326  UINT32 value;
327  IoResultCodes resultCode;
328 } __attribute__((__packed__));
330 
332 {
333  UINT32 ioAddress; //Group address. Example: '1001' will write OG#1 (Bits 10010 through 10017)
334  UINT32 ioValue;
335 } __attribute__((__packed__));
337 
339 {
340  IoResultCodes resultCode;
341 } __attribute__((__packed__));
343 
344 struct _SmBodyMotoIoCtrlReply // ROS_MSG_MOTO_IOCTRL_REPLY = 2011
345 {
346  SmResultType result; // High level result code
347  int subcode; // More detailed result code (optional)
348 } __attribute__((__packed__));
350 
352 {
353  UINT32 registerNumber; //Actual register index. Do not add 1000000 to this value. (Example: 123 = M123)
354 } __attribute__((__packed__));
356 
358 {
359  UINT32 value;
360  IoResultCodes resultCode;
361 } __attribute__((__packed__));
363 
365 {
366  UINT32 registerNumber; //Actual register index. Do not add 1000000 to this value. (Example: 123 = M123)
367  UINT32 value;
368 } __attribute__((__packed__));
370 
372 {
373  IoResultCodes resultCode;
374 } __attribute__((__packed__));
376 
377 //--------------
378 // DH Parameters
379 //--------------
380 
382 {
384 } __attribute__((__packed__));
386 
387 //--------------
388 // Body Union
389 //--------------
390 
391 typedef union
392 {
415 } SmBody;
416 
417 //-------------------
418 // SimpleMsg Section
419 //-------------------
421 {
425 } __attribute__((__packed__));
426 typedef struct _SimpleMsg SimpleMsg;
427 
428 
429 //-------------------
430 // Function Section
431 //-------------------
432 
433 extern int Ros_SimpleMsg_JointFeedback(CtrlGroup* ctrlGroup, SimpleMsg* sendMsg);
434 extern void Ros_SimpleMsg_JointFeedbackEx_Init(int numberOfGroups, SimpleMsg* sendMsg);
435 extern int Ros_SimpleMsg_JointFeedbackEx_Build(int groupIndex, SimpleMsg* src_msgFeedback, SimpleMsg* dst_msgExtendedFeedback);
436 
437 extern int Ros_SimpleMsg_MotionReply(SimpleMsg* receiveMsg, int result, int subcode, SimpleMsg* replyMsg, int ctrlGrp);
438 extern int Ros_SimpleMsg_IoReply(int result, int subcode, SimpleMsg* replyMsg);
439 
440 //Uncomment the DEBUG definition to enable debug-messages at runtime
441 //#define DEBUG 1
442 
443 #ifdef DEBUG
444 #warning Dont forget to disable the DEBUG flag
445 // function to dump data structure for debugging
446 extern void Ros_SimpleMsg_DumpTrajPtFull(SmBodyJointTrajPtFull* data);
447 #endif
448 
449 #endif
SmMsgType msgType
typedef __attribute__
SmBodyMotoWriteIOGroup writeIOGroup
int Ros_SimpleMsg_JointFeedback(CtrlGroup *ctrlGroup, SimpleMsg *sendMsg)
Definition: SimpleMessage.c:51
SmBodyMotoReadIOBit readIOBit
float pos[ROS_MAX_JOINT]
SmNotReadySubcode
float acc[ROS_MAX_JOINT]
SmBodyMotoReadIOMRegisterReply readRegisterReply
SmBodyJointTrajPtFull jointTrajData
SmCommandType command
SmBodyJointFeedbackEx jointFeedbackEx
SmBodyJointTrajPtExData jointTrajPtData[MOT_MAX_GR]
SmPrefix prefix
SmCommandType
SmBodyMotoMotionCtrl motionCtrl
SmBodyMotoReadIOBitReply readIOBitReply
int subcode
SmBodyJointTrajPtFullEx jointTrajDataEx
DH_PARAMETERS dhParameters[MOT_MAX_GR]
SmInvalidSubCode
SmBodyMotoMotionReply motionReply
SmBodyRobotStatus robotStatus
int Ros_SimpleMsg_IoReply(int result, int subcode, SimpleMsg *replyMsg)
#define ROS_MAX_JOINT
Definition: SimpleMessage.h:35
SmResultType
SmBodySelectTool selectTool
float data[ROS_MAX_JOINT]
SmBodyJointFeedback jointFeedback
SmHeader header
SmResultType result
SmReplyType replyType
FlagsValidFields validFields
SmBodyMotoWriteIOBitReply writeIOBitReply
SmBodyMotoGetDhParameters dhParameters
SmCommType commType
#define MOT_MAX_GR
Definition: SimpleMessage.h:36
SmBodyMotoWriteIOMRegister writeRegister
SmMsgType
Definition: SimpleMessage.h:52
FlagsValidFields validFields
int Ros_SimpleMsg_MotionReply(SimpleMsg *receiveMsg, int result, int subcode, SimpleMsg *replyMsg, int ctrlGrp)
FlagsValidFields
SmBodyMotoWriteIOGroupReply writeIOGroupReply
SmBodyMotoIoCtrlReply ioCtrlReply
SmBodyMotoReadIOGroup readIOGroup
IoResultCodes
SmReplyType
Definition: SimpleMessage.h:93
SmBodyMotoReadIOMRegister readRegister
SmCommType
Definition: SimpleMessage.h:84
SmBodyMotoWriteIOMRegisterReply writeRegisterReply
void Ros_SimpleMsg_JointFeedbackEx_Init(int numberOfGroups, SimpleMsg *sendMsg)
Definition: SimpleMessage.c:90
SmBodyMotoReadIOGroupReply readIOGroupReply
FlagsValidFields validFields
float vel[ROS_MAX_JOINT]
int Ros_SimpleMsg_JointFeedbackEx_Build(int groupIndex, SimpleMsg *src_msgFeedback, SimpleMsg *dst_msgExtendedFeedback)
SmBodyMotoWriteIOBit writeIOBit


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:44