added 1 custom message
Fork of ros_lib_kinetic by
gazebo_msgs/ModelState.h@2:af816ffd33df, 2017-05-19 (annotated)
- Committer:
- randalthor
- Date:
- Fri May 19 08:59:12 2017 +0000
- Revision:
- 2:af816ffd33df
- Parent:
- 0:9e9b7db60fd5
custom message mobile robot added for ITU cyber physical lab
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_gazebo_msgs_ModelState_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_gazebo_msgs_ModelState_h |
garyservin | 0:9e9b7db60fd5 | 3 | |
garyservin | 0:9e9b7db60fd5 | 4 | #include <stdint.h> |
garyservin | 0:9e9b7db60fd5 | 5 | #include <string.h> |
garyservin | 0:9e9b7db60fd5 | 6 | #include <stdlib.h> |
garyservin | 0:9e9b7db60fd5 | 7 | #include "ros/msg.h" |
garyservin | 0:9e9b7db60fd5 | 8 | #include "geometry_msgs/Pose.h" |
garyservin | 0:9e9b7db60fd5 | 9 | #include "geometry_msgs/Twist.h" |
garyservin | 0:9e9b7db60fd5 | 10 | |
garyservin | 0:9e9b7db60fd5 | 11 | namespace gazebo_msgs |
garyservin | 0:9e9b7db60fd5 | 12 | { |
garyservin | 0:9e9b7db60fd5 | 13 | |
garyservin | 0:9e9b7db60fd5 | 14 | class ModelState : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 15 | { |
garyservin | 0:9e9b7db60fd5 | 16 | public: |
garyservin | 0:9e9b7db60fd5 | 17 | typedef const char* _model_name_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _model_name_type model_name; |
garyservin | 0:9e9b7db60fd5 | 19 | typedef geometry_msgs::Pose _pose_type; |
garyservin | 0:9e9b7db60fd5 | 20 | _pose_type pose; |
garyservin | 0:9e9b7db60fd5 | 21 | typedef geometry_msgs::Twist _twist_type; |
garyservin | 0:9e9b7db60fd5 | 22 | _twist_type twist; |
garyservin | 0:9e9b7db60fd5 | 23 | typedef const char* _reference_frame_type; |
garyservin | 0:9e9b7db60fd5 | 24 | _reference_frame_type reference_frame; |
garyservin | 0:9e9b7db60fd5 | 25 | |
garyservin | 0:9e9b7db60fd5 | 26 | ModelState(): |
garyservin | 0:9e9b7db60fd5 | 27 | model_name(""), |
garyservin | 0:9e9b7db60fd5 | 28 | pose(), |
garyservin | 0:9e9b7db60fd5 | 29 | twist(), |
garyservin | 0:9e9b7db60fd5 | 30 | reference_frame("") |
garyservin | 0:9e9b7db60fd5 | 31 | { |
garyservin | 0:9e9b7db60fd5 | 32 | } |
garyservin | 0:9e9b7db60fd5 | 33 | |
garyservin | 0:9e9b7db60fd5 | 34 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 35 | { |
garyservin | 0:9e9b7db60fd5 | 36 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 37 | uint32_t length_model_name = strlen(this->model_name); |
garyservin | 0:9e9b7db60fd5 | 38 | varToArr(outbuffer + offset, length_model_name); |
garyservin | 0:9e9b7db60fd5 | 39 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 40 | memcpy(outbuffer + offset, this->model_name, length_model_name); |
garyservin | 0:9e9b7db60fd5 | 41 | offset += length_model_name; |
garyservin | 0:9e9b7db60fd5 | 42 | offset += this->pose.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 43 | offset += this->twist.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 44 | uint32_t length_reference_frame = strlen(this->reference_frame); |
garyservin | 0:9e9b7db60fd5 | 45 | varToArr(outbuffer + offset, length_reference_frame); |
garyservin | 0:9e9b7db60fd5 | 46 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 47 | memcpy(outbuffer + offset, this->reference_frame, length_reference_frame); |
garyservin | 0:9e9b7db60fd5 | 48 | offset += length_reference_frame; |
garyservin | 0:9e9b7db60fd5 | 49 | return offset; |
garyservin | 0:9e9b7db60fd5 | 50 | } |
garyservin | 0:9e9b7db60fd5 | 51 | |
garyservin | 0:9e9b7db60fd5 | 52 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 53 | { |
garyservin | 0:9e9b7db60fd5 | 54 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 55 | uint32_t length_model_name; |
garyservin | 0:9e9b7db60fd5 | 56 | arrToVar(length_model_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 57 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 58 | for(unsigned int k= offset; k< offset+length_model_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 59 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 60 | } |
garyservin | 0:9e9b7db60fd5 | 61 | inbuffer[offset+length_model_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 62 | this->model_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 63 | offset += length_model_name; |
garyservin | 0:9e9b7db60fd5 | 64 | offset += this->pose.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 65 | offset += this->twist.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 66 | uint32_t length_reference_frame; |
garyservin | 0:9e9b7db60fd5 | 67 | arrToVar(length_reference_frame, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 68 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 69 | for(unsigned int k= offset; k< offset+length_reference_frame; ++k){ |
garyservin | 0:9e9b7db60fd5 | 70 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 71 | } |
garyservin | 0:9e9b7db60fd5 | 72 | inbuffer[offset+length_reference_frame-1]=0; |
garyservin | 0:9e9b7db60fd5 | 73 | this->reference_frame = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 74 | offset += length_reference_frame; |
garyservin | 0:9e9b7db60fd5 | 75 | return offset; |
garyservin | 0:9e9b7db60fd5 | 76 | } |
garyservin | 0:9e9b7db60fd5 | 77 | |
garyservin | 0:9e9b7db60fd5 | 78 | const char * getType(){ return "gazebo_msgs/ModelState"; }; |
garyservin | 0:9e9b7db60fd5 | 79 | const char * getMD5(){ return "9330fd35f2fcd82d457e54bd54e10593"; }; |
garyservin | 0:9e9b7db60fd5 | 80 | |
garyservin | 0:9e9b7db60fd5 | 81 | }; |
garyservin | 0:9e9b7db60fd5 | 82 | |
garyservin | 0:9e9b7db60fd5 | 83 | } |
garyservin | 0:9e9b7db60fd5 | 84 | #endif |