rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
moveit_msgs/AttachedCollisionObject.h@0:30537dec6e0b, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Revision:
- 0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_moveit_msgs_AttachedCollisionObject_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_AttachedCollisionObject_h |
akashvibhute | 0:30537dec6e0b | 3 | |
akashvibhute | 0:30537dec6e0b | 4 | #include <stdint.h> |
akashvibhute | 0:30537dec6e0b | 5 | #include <string.h> |
akashvibhute | 0:30537dec6e0b | 6 | #include <stdlib.h> |
akashvibhute | 0:30537dec6e0b | 7 | #include "ros/msg.h" |
akashvibhute | 0:30537dec6e0b | 8 | #include "moveit_msgs/CollisionObject.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "trajectory_msgs/JointTrajectory.h" |
akashvibhute | 0:30537dec6e0b | 10 | |
akashvibhute | 0:30537dec6e0b | 11 | namespace moveit_msgs |
akashvibhute | 0:30537dec6e0b | 12 | { |
akashvibhute | 0:30537dec6e0b | 13 | |
akashvibhute | 0:30537dec6e0b | 14 | class AttachedCollisionObject : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 15 | { |
akashvibhute | 0:30537dec6e0b | 16 | public: |
akashvibhute | 0:30537dec6e0b | 17 | const char* link_name; |
akashvibhute | 0:30537dec6e0b | 18 | moveit_msgs::CollisionObject object; |
akashvibhute | 0:30537dec6e0b | 19 | uint8_t touch_links_length; |
akashvibhute | 0:30537dec6e0b | 20 | char* st_touch_links; |
akashvibhute | 0:30537dec6e0b | 21 | char* * touch_links; |
akashvibhute | 0:30537dec6e0b | 22 | trajectory_msgs::JointTrajectory detach_posture; |
akashvibhute | 0:30537dec6e0b | 23 | float weight; |
akashvibhute | 0:30537dec6e0b | 24 | |
akashvibhute | 0:30537dec6e0b | 25 | AttachedCollisionObject(): |
akashvibhute | 0:30537dec6e0b | 26 | link_name(""), |
akashvibhute | 0:30537dec6e0b | 27 | object(), |
akashvibhute | 0:30537dec6e0b | 28 | touch_links_length(0), touch_links(NULL), |
akashvibhute | 0:30537dec6e0b | 29 | detach_posture(), |
akashvibhute | 0:30537dec6e0b | 30 | weight(0) |
akashvibhute | 0:30537dec6e0b | 31 | { |
akashvibhute | 0:30537dec6e0b | 32 | } |
akashvibhute | 0:30537dec6e0b | 33 | |
akashvibhute | 0:30537dec6e0b | 34 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 35 | { |
akashvibhute | 0:30537dec6e0b | 36 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 37 | uint32_t length_link_name = strlen(this->link_name); |
akashvibhute | 0:30537dec6e0b | 38 | memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 39 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 40 | memcpy(outbuffer + offset, this->link_name, length_link_name); |
akashvibhute | 0:30537dec6e0b | 41 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 42 | offset += this->object.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 43 | *(outbuffer + offset++) = touch_links_length; |
akashvibhute | 0:30537dec6e0b | 44 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 45 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 46 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 47 | for( uint8_t i = 0; i < touch_links_length; i++){ |
akashvibhute | 0:30537dec6e0b | 48 | uint32_t length_touch_linksi = strlen(this->touch_links[i]); |
akashvibhute | 0:30537dec6e0b | 49 | memcpy(outbuffer + offset, &length_touch_linksi, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 50 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 51 | memcpy(outbuffer + offset, this->touch_links[i], length_touch_linksi); |
akashvibhute | 0:30537dec6e0b | 52 | offset += length_touch_linksi; |
akashvibhute | 0:30537dec6e0b | 53 | } |
akashvibhute | 0:30537dec6e0b | 54 | offset += this->detach_posture.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 55 | offset += serializeAvrFloat64(outbuffer + offset, this->weight); |
akashvibhute | 0:30537dec6e0b | 56 | return offset; |
akashvibhute | 0:30537dec6e0b | 57 | } |
akashvibhute | 0:30537dec6e0b | 58 | |
akashvibhute | 0:30537dec6e0b | 59 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 60 | { |
akashvibhute | 0:30537dec6e0b | 61 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 62 | uint32_t length_link_name; |
akashvibhute | 0:30537dec6e0b | 63 | memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 64 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 65 | for(unsigned int k= offset; k< offset+length_link_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 66 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 67 | } |
akashvibhute | 0:30537dec6e0b | 68 | inbuffer[offset+length_link_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 69 | this->link_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 70 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 71 | offset += this->object.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 72 | uint8_t touch_links_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 73 | if(touch_links_lengthT > touch_links_length) |
akashvibhute | 0:30537dec6e0b | 74 | this->touch_links = (char**)realloc(this->touch_links, touch_links_lengthT * sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 75 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 76 | touch_links_length = touch_links_lengthT; |
akashvibhute | 0:30537dec6e0b | 77 | for( uint8_t i = 0; i < touch_links_length; i++){ |
akashvibhute | 0:30537dec6e0b | 78 | uint32_t length_st_touch_links; |
akashvibhute | 0:30537dec6e0b | 79 | memcpy(&length_st_touch_links, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 80 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 81 | for(unsigned int k= offset; k< offset+length_st_touch_links; ++k){ |
akashvibhute | 0:30537dec6e0b | 82 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 83 | } |
akashvibhute | 0:30537dec6e0b | 84 | inbuffer[offset+length_st_touch_links-1]=0; |
akashvibhute | 0:30537dec6e0b | 85 | this->st_touch_links = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 86 | offset += length_st_touch_links; |
akashvibhute | 0:30537dec6e0b | 87 | memcpy( &(this->touch_links[i]), &(this->st_touch_links), sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 88 | } |
akashvibhute | 0:30537dec6e0b | 89 | offset += this->detach_posture.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 90 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); |
akashvibhute | 0:30537dec6e0b | 91 | return offset; |
akashvibhute | 0:30537dec6e0b | 92 | } |
akashvibhute | 0:30537dec6e0b | 93 | |
akashvibhute | 0:30537dec6e0b | 94 | const char * getType(){ return "moveit_msgs/AttachedCollisionObject"; }; |
akashvibhute | 0:30537dec6e0b | 95 | const char * getMD5(){ return "3ceac60b21e85bbd6c5b0ab9d476b752"; }; |
akashvibhute | 0:30537dec6e0b | 96 | |
akashvibhute | 0:30537dec6e0b | 97 | }; |
akashvibhute | 0:30537dec6e0b | 98 | |
akashvibhute | 0:30537dec6e0b | 99 | } |
akashvibhute | 0:30537dec6e0b | 100 | #endif |