catchrobo2022 / Mbed 2 deprecated catchrobo2022_mbed

Dependencies:   mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers PositionConstraint.h Source File

PositionConstraint.h

00001 #ifndef _ROS_moveit_msgs_PositionConstraint_h
00002 #define _ROS_moveit_msgs_PositionConstraint_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "geometry_msgs/Vector3.h"
00010 #include "moveit_msgs/BoundingVolume.h"
00011 
00012 namespace moveit_msgs
00013 {
00014 
00015   class PositionConstraint : public ros::Msg
00016   {
00017     public:
00018       typedef std_msgs::Header _header_type;
00019       _header_type header;
00020       typedef const char* _link_name_type;
00021       _link_name_type link_name;
00022       typedef geometry_msgs::Vector3 _target_point_offset_type;
00023       _target_point_offset_type target_point_offset;
00024       typedef moveit_msgs::BoundingVolume _constraint_region_type;
00025       _constraint_region_type constraint_region;
00026       typedef double _weight_type;
00027       _weight_type weight;
00028 
00029     PositionConstraint():
00030       header(),
00031       link_name(""),
00032       target_point_offset(),
00033       constraint_region(),
00034       weight(0)
00035     {
00036     }
00037 
00038     virtual int serialize(unsigned char *outbuffer) const
00039     {
00040       int offset = 0;
00041       offset += this->header.serialize(outbuffer + offset);
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->target_point_offset.serialize(outbuffer + offset);
00048       offset += this->constraint_region.serialize(outbuffer + offset);
00049       union {
00050         double real;
00051         uint64_t base;
00052       } u_weight;
00053       u_weight.real = this->weight;
00054       *(outbuffer + offset + 0) = (u_weight.base >> (8 * 0)) & 0xFF;
00055       *(outbuffer + offset + 1) = (u_weight.base >> (8 * 1)) & 0xFF;
00056       *(outbuffer + offset + 2) = (u_weight.base >> (8 * 2)) & 0xFF;
00057       *(outbuffer + offset + 3) = (u_weight.base >> (8 * 3)) & 0xFF;
00058       *(outbuffer + offset + 4) = (u_weight.base >> (8 * 4)) & 0xFF;
00059       *(outbuffer + offset + 5) = (u_weight.base >> (8 * 5)) & 0xFF;
00060       *(outbuffer + offset + 6) = (u_weight.base >> (8 * 6)) & 0xFF;
00061       *(outbuffer + offset + 7) = (u_weight.base >> (8 * 7)) & 0xFF;
00062       offset += sizeof(this->weight);
00063       return offset;
00064     }
00065 
00066     virtual int deserialize(unsigned char *inbuffer)
00067     {
00068       int offset = 0;
00069       offset += this->header.deserialize(inbuffer + offset);
00070       uint32_t length_link_name;
00071       arrToVar(length_link_name, (inbuffer + offset));
00072       offset += 4;
00073       for(unsigned int k= offset; k< offset+length_link_name; ++k){
00074           inbuffer[k-1]=inbuffer[k];
00075       }
00076       inbuffer[offset+length_link_name-1]=0;
00077       this->link_name = (char *)(inbuffer + offset-1);
00078       offset += length_link_name;
00079       offset += this->target_point_offset.deserialize(inbuffer + offset);
00080       offset += this->constraint_region.deserialize(inbuffer + offset);
00081       union {
00082         double real;
00083         uint64_t base;
00084       } u_weight;
00085       u_weight.base = 0;
00086       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00087       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00088       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00089       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00090       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00091       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00092       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00093       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00094       this->weight = u_weight.real;
00095       offset += sizeof(this->weight);
00096      return offset;
00097     }
00098 
00099     virtual const char * getType(){ return "moveit_msgs/PositionConstraint"; };
00100     virtual const char * getMD5(){ return "c83edf208d87d3aa3169f47775a58e6a"; };
00101 
00102   };
00103 
00104 }
00105 #endif