catchrobo2022 / Mbed 2 deprecated catchrobo2022_mbed

Dependencies:   mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers VisibilityConstraint.h Source File

VisibilityConstraint.h

00001 #ifndef _ROS_moveit_msgs_VisibilityConstraint_h
00002 #define _ROS_moveit_msgs_VisibilityConstraint_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/PoseStamped.h"
00009 
00010 namespace moveit_msgs
00011 {
00012 
00013   class VisibilityConstraint : public ros::Msg
00014   {
00015     public:
00016       typedef double _target_radius_type;
00017       _target_radius_type target_radius;
00018       typedef geometry_msgs::PoseStamped _target_pose_type;
00019       _target_pose_type target_pose;
00020       typedef int32_t _cone_sides_type;
00021       _cone_sides_type cone_sides;
00022       typedef geometry_msgs::PoseStamped _sensor_pose_type;
00023       _sensor_pose_type sensor_pose;
00024       typedef double _max_view_angle_type;
00025       _max_view_angle_type max_view_angle;
00026       typedef double _max_range_angle_type;
00027       _max_range_angle_type max_range_angle;
00028       typedef uint8_t _sensor_view_direction_type;
00029       _sensor_view_direction_type sensor_view_direction;
00030       typedef double _weight_type;
00031       _weight_type weight;
00032       enum { SENSOR_Z = 0 };
00033       enum { SENSOR_Y = 1 };
00034       enum { SENSOR_X = 2 };
00035 
00036     VisibilityConstraint():
00037       target_radius(0),
00038       target_pose(),
00039       cone_sides(0),
00040       sensor_pose(),
00041       max_view_angle(0),
00042       max_range_angle(0),
00043       sensor_view_direction(0),
00044       weight(0)
00045     {
00046     }
00047 
00048     virtual int serialize(unsigned char *outbuffer) const
00049     {
00050       int offset = 0;
00051       union {
00052         double real;
00053         uint64_t base;
00054       } u_target_radius;
00055       u_target_radius.real = this->target_radius;
00056       *(outbuffer + offset + 0) = (u_target_radius.base >> (8 * 0)) & 0xFF;
00057       *(outbuffer + offset + 1) = (u_target_radius.base >> (8 * 1)) & 0xFF;
00058       *(outbuffer + offset + 2) = (u_target_radius.base >> (8 * 2)) & 0xFF;
00059       *(outbuffer + offset + 3) = (u_target_radius.base >> (8 * 3)) & 0xFF;
00060       *(outbuffer + offset + 4) = (u_target_radius.base >> (8 * 4)) & 0xFF;
00061       *(outbuffer + offset + 5) = (u_target_radius.base >> (8 * 5)) & 0xFF;
00062       *(outbuffer + offset + 6) = (u_target_radius.base >> (8 * 6)) & 0xFF;
00063       *(outbuffer + offset + 7) = (u_target_radius.base >> (8 * 7)) & 0xFF;
00064       offset += sizeof(this->target_radius);
00065       offset += this->target_pose.serialize(outbuffer + offset);
00066       union {
00067         int32_t real;
00068         uint32_t base;
00069       } u_cone_sides;
00070       u_cone_sides.real = this->cone_sides;
00071       *(outbuffer + offset + 0) = (u_cone_sides.base >> (8 * 0)) & 0xFF;
00072       *(outbuffer + offset + 1) = (u_cone_sides.base >> (8 * 1)) & 0xFF;
00073       *(outbuffer + offset + 2) = (u_cone_sides.base >> (8 * 2)) & 0xFF;
00074       *(outbuffer + offset + 3) = (u_cone_sides.base >> (8 * 3)) & 0xFF;
00075       offset += sizeof(this->cone_sides);
00076       offset += this->sensor_pose.serialize(outbuffer + offset);
00077       union {
00078         double real;
00079         uint64_t base;
00080       } u_max_view_angle;
00081       u_max_view_angle.real = this->max_view_angle;
00082       *(outbuffer + offset + 0) = (u_max_view_angle.base >> (8 * 0)) & 0xFF;
00083       *(outbuffer + offset + 1) = (u_max_view_angle.base >> (8 * 1)) & 0xFF;
00084       *(outbuffer + offset + 2) = (u_max_view_angle.base >> (8 * 2)) & 0xFF;
00085       *(outbuffer + offset + 3) = (u_max_view_angle.base >> (8 * 3)) & 0xFF;
00086       *(outbuffer + offset + 4) = (u_max_view_angle.base >> (8 * 4)) & 0xFF;
00087       *(outbuffer + offset + 5) = (u_max_view_angle.base >> (8 * 5)) & 0xFF;
00088       *(outbuffer + offset + 6) = (u_max_view_angle.base >> (8 * 6)) & 0xFF;
00089       *(outbuffer + offset + 7) = (u_max_view_angle.base >> (8 * 7)) & 0xFF;
00090       offset += sizeof(this->max_view_angle);
00091       union {
00092         double real;
00093         uint64_t base;
00094       } u_max_range_angle;
00095       u_max_range_angle.real = this->max_range_angle;
00096       *(outbuffer + offset + 0) = (u_max_range_angle.base >> (8 * 0)) & 0xFF;
00097       *(outbuffer + offset + 1) = (u_max_range_angle.base >> (8 * 1)) & 0xFF;
00098       *(outbuffer + offset + 2) = (u_max_range_angle.base >> (8 * 2)) & 0xFF;
00099       *(outbuffer + offset + 3) = (u_max_range_angle.base >> (8 * 3)) & 0xFF;
00100       *(outbuffer + offset + 4) = (u_max_range_angle.base >> (8 * 4)) & 0xFF;
00101       *(outbuffer + offset + 5) = (u_max_range_angle.base >> (8 * 5)) & 0xFF;
00102       *(outbuffer + offset + 6) = (u_max_range_angle.base >> (8 * 6)) & 0xFF;
00103       *(outbuffer + offset + 7) = (u_max_range_angle.base >> (8 * 7)) & 0xFF;
00104       offset += sizeof(this->max_range_angle);
00105       *(outbuffer + offset + 0) = (this->sensor_view_direction >> (8 * 0)) & 0xFF;
00106       offset += sizeof(this->sensor_view_direction);
00107       union {
00108         double real;
00109         uint64_t base;
00110       } u_weight;
00111       u_weight.real = this->weight;
00112       *(outbuffer + offset + 0) = (u_weight.base >> (8 * 0)) & 0xFF;
00113       *(outbuffer + offset + 1) = (u_weight.base >> (8 * 1)) & 0xFF;
00114       *(outbuffer + offset + 2) = (u_weight.base >> (8 * 2)) & 0xFF;
00115       *(outbuffer + offset + 3) = (u_weight.base >> (8 * 3)) & 0xFF;
00116       *(outbuffer + offset + 4) = (u_weight.base >> (8 * 4)) & 0xFF;
00117       *(outbuffer + offset + 5) = (u_weight.base >> (8 * 5)) & 0xFF;
00118       *(outbuffer + offset + 6) = (u_weight.base >> (8 * 6)) & 0xFF;
00119       *(outbuffer + offset + 7) = (u_weight.base >> (8 * 7)) & 0xFF;
00120       offset += sizeof(this->weight);
00121       return offset;
00122     }
00123 
00124     virtual int deserialize(unsigned char *inbuffer)
00125     {
00126       int offset = 0;
00127       union {
00128         double real;
00129         uint64_t base;
00130       } u_target_radius;
00131       u_target_radius.base = 0;
00132       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00133       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00134       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00135       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00136       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00137       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00138       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00139       u_target_radius.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00140       this->target_radius = u_target_radius.real;
00141       offset += sizeof(this->target_radius);
00142       offset += this->target_pose.deserialize(inbuffer + offset);
00143       union {
00144         int32_t real;
00145         uint32_t base;
00146       } u_cone_sides;
00147       u_cone_sides.base = 0;
00148       u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00149       u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00150       u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00151       u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00152       this->cone_sides = u_cone_sides.real;
00153       offset += sizeof(this->cone_sides);
00154       offset += this->sensor_pose.deserialize(inbuffer + offset);
00155       union {
00156         double real;
00157         uint64_t base;
00158       } u_max_view_angle;
00159       u_max_view_angle.base = 0;
00160       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00161       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00162       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00163       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00164       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00165       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00166       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00167       u_max_view_angle.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00168       this->max_view_angle = u_max_view_angle.real;
00169       offset += sizeof(this->max_view_angle);
00170       union {
00171         double real;
00172         uint64_t base;
00173       } u_max_range_angle;
00174       u_max_range_angle.base = 0;
00175       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00176       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00177       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00178       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00179       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00180       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00181       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00182       u_max_range_angle.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00183       this->max_range_angle = u_max_range_angle.real;
00184       offset += sizeof(this->max_range_angle);
00185       this->sensor_view_direction =  ((uint8_t) (*(inbuffer + offset)));
00186       offset += sizeof(this->sensor_view_direction);
00187       union {
00188         double real;
00189         uint64_t base;
00190       } u_weight;
00191       u_weight.base = 0;
00192       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00193       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00194       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00195       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00196       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00197       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00198       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00199       u_weight.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00200       this->weight = u_weight.real;
00201       offset += sizeof(this->weight);
00202      return offset;
00203     }
00204 
00205     virtual const char * getType(){ return "moveit_msgs/VisibilityConstraint"; };
00206     virtual const char * getMD5(){ return "62cda903bfe31ff2e5fcdc3810d577ad"; };
00207 
00208   };
00209 
00210 }
00211 #endif