Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
AttachedCollisionObject.h
00001 #ifndef _ROS_moveit_msgs_AttachedCollisionObject_h 00002 #define _ROS_moveit_msgs_AttachedCollisionObject_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "moveit_msgs/CollisionObject.h" 00009 #include "trajectory_msgs/JointTrajectory.h" 00010 00011 namespace moveit_msgs 00012 { 00013 00014 class AttachedCollisionObject : public ros::Msg 00015 { 00016 public: 00017 typedef const char* _link_name_type; 00018 _link_name_type link_name; 00019 typedef moveit_msgs::CollisionObject _object_type; 00020 _object_type object; 00021 uint32_t touch_links_length; 00022 typedef char* _touch_links_type; 00023 _touch_links_type st_touch_links; 00024 _touch_links_type * touch_links; 00025 typedef trajectory_msgs::JointTrajectory _detach_posture_type; 00026 _detach_posture_type detach_posture; 00027 typedef double _weight_type; 00028 _weight_type weight; 00029 00030 AttachedCollisionObject(): 00031 link_name(""), 00032 object(), 00033 touch_links_length(0), touch_links(NULL), 00034 detach_posture(), 00035 weight(0) 00036 { 00037 } 00038 00039 virtual int serialize(unsigned char *outbuffer) const 00040 { 00041 int offset = 0; 00042 uint32_t length_link_name = strlen(this->link_name); 00043 varToArr(outbuffer + offset, length_link_name); 00044 offset += 4; 00045 memcpy(outbuffer + offset, this->link_name, length_link_name); 00046 offset += length_link_name; 00047 offset += this->object.serialize(outbuffer + offset); 00048 *(outbuffer + offset + 0) = (this->touch_links_length >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (this->touch_links_length >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (this->touch_links_length >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (this->touch_links_length >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->touch_links_length); 00053 for( uint32_t i = 0; i < touch_links_length; i++){ 00054 uint32_t length_touch_linksi = strlen(this->touch_links[i]); 00055 varToArr(outbuffer + offset, length_touch_linksi); 00056 offset += 4; 00057 memcpy(outbuffer + offset, this->touch_links[i], length_touch_linksi); 00058 offset += length_touch_linksi; 00059 } 00060 offset += this->detach_posture.serialize(outbuffer + offset); 00061 union { 00062 double real; 00063 uint64_t base; 00064 } u_weight; 00065 u_weight.real = this->weight; 00066 *(outbuffer + offset + 0) = (u_weight.base >> (8 * 0)) & 0xFF; 00067 *(outbuffer + offset + 1) = (u_weight.base >> (8 * 1)) & 0xFF; 00068 *(outbuffer + offset + 2) = (u_weight.base >> (8 * 2)) & 0xFF; 00069 *(outbuffer + offset + 3) = (u_weight.base >> (8 * 3)) & 0xFF; 00070 *(outbuffer + offset + 4) = (u_weight.base >> (8 * 4)) & 0xFF; 00071 *(outbuffer + offset + 5) = (u_weight.base >> (8 * 5)) & 0xFF; 00072 *(outbuffer + offset + 6) = (u_weight.base >> (8 * 6)) & 0xFF; 00073 *(outbuffer + offset + 7) = (u_weight.base >> (8 * 7)) & 0xFF; 00074 offset += sizeof(this->weight); 00075 return offset; 00076 } 00077 00078 virtual int deserialize(unsigned char *inbuffer) 00079 { 00080 int offset = 0; 00081 uint32_t length_link_name; 00082 arrToVar(length_link_name, (inbuffer + offset)); 00083 offset += 4; 00084 for(unsigned int k= offset; k< offset+length_link_name; ++k){ 00085 inbuffer[k-1]=inbuffer[k]; 00086 } 00087 inbuffer[offset+length_link_name-1]=0; 00088 this->link_name = (char *)(inbuffer + offset-1); 00089 offset += length_link_name; 00090 offset += this->object.deserialize(inbuffer + offset); 00091 uint32_t touch_links_lengthT = ((uint32_t) (*(inbuffer + offset))); 00092 touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00093 touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00094 touch_links_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00095 offset += sizeof(this->touch_links_length); 00096 if(touch_links_lengthT > touch_links_length) 00097 this->touch_links = (char**)realloc(this->touch_links, touch_links_lengthT * sizeof(char*)); 00098 touch_links_length = touch_links_lengthT; 00099 for( uint32_t i = 0; i < touch_links_length; i++){ 00100 uint32_t length_st_touch_links; 00101 arrToVar(length_st_touch_links, (inbuffer + offset)); 00102 offset += 4; 00103 for(unsigned int k= offset; k< offset+length_st_touch_links; ++k){ 00104 inbuffer[k-1]=inbuffer[k]; 00105 } 00106 inbuffer[offset+length_st_touch_links-1]=0; 00107 this->st_touch_links = (char *)(inbuffer + offset-1); 00108 offset += length_st_touch_links; 00109 memcpy( &(this->touch_links[i]), &(this->st_touch_links), sizeof(char*)); 00110 } 00111 offset += this->detach_posture.deserialize(inbuffer + offset); 00112 union { 00113 double real; 00114 uint64_t base; 00115 } u_weight; 00116 u_weight.base = 0; 00117 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00118 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00119 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00120 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00121 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00122 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00123 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00124 u_weight.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00125 this->weight = u_weight.real; 00126 offset += sizeof(this->weight); 00127 return offset; 00128 } 00129 00130 virtual const char * getType(){ return "moveit_msgs/AttachedCollisionObject"; }; 00131 virtual const char * getMD5(){ return "3ceac60b21e85bbd6c5b0ab9d476b752"; }; 00132 00133 }; 00134 00135 } 00136 #endif
Generated on Mon Sep 26 2022 13:46:59 by
