rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

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?

UserRevisionLine numberNew contents of line
akashvibhute 0:30537dec6e0b 1 #ifndef _ROS_moveit_msgs_VisibilityConstraint_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_VisibilityConstraint_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 "geometry_msgs/PoseStamped.h"
akashvibhute 0:30537dec6e0b 9
akashvibhute 0:30537dec6e0b 10 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 11 {
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class VisibilityConstraint : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 float target_radius;
akashvibhute 0:30537dec6e0b 17 geometry_msgs::PoseStamped target_pose;
akashvibhute 0:30537dec6e0b 18 int32_t cone_sides;
akashvibhute 0:30537dec6e0b 19 geometry_msgs::PoseStamped sensor_pose;
akashvibhute 0:30537dec6e0b 20 float max_view_angle;
akashvibhute 0:30537dec6e0b 21 float max_range_angle;
akashvibhute 0:30537dec6e0b 22 uint8_t sensor_view_direction;
akashvibhute 0:30537dec6e0b 23 float weight;
akashvibhute 0:30537dec6e0b 24 enum { SENSOR_Z = 0 };
akashvibhute 0:30537dec6e0b 25 enum { SENSOR_Y = 1 };
akashvibhute 0:30537dec6e0b 26 enum { SENSOR_X = 2 };
akashvibhute 0:30537dec6e0b 27
akashvibhute 0:30537dec6e0b 28 VisibilityConstraint():
akashvibhute 0:30537dec6e0b 29 target_radius(0),
akashvibhute 0:30537dec6e0b 30 target_pose(),
akashvibhute 0:30537dec6e0b 31 cone_sides(0),
akashvibhute 0:30537dec6e0b 32 sensor_pose(),
akashvibhute 0:30537dec6e0b 33 max_view_angle(0),
akashvibhute 0:30537dec6e0b 34 max_range_angle(0),
akashvibhute 0:30537dec6e0b 35 sensor_view_direction(0),
akashvibhute 0:30537dec6e0b 36 weight(0)
akashvibhute 0:30537dec6e0b 37 {
akashvibhute 0:30537dec6e0b 38 }
akashvibhute 0:30537dec6e0b 39
akashvibhute 0:30537dec6e0b 40 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 41 {
akashvibhute 0:30537dec6e0b 42 int offset = 0;
akashvibhute 0:30537dec6e0b 43 offset += serializeAvrFloat64(outbuffer + offset, this->target_radius);
akashvibhute 0:30537dec6e0b 44 offset += this->target_pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 45 union {
akashvibhute 0:30537dec6e0b 46 int32_t real;
akashvibhute 0:30537dec6e0b 47 uint32_t base;
akashvibhute 0:30537dec6e0b 48 } u_cone_sides;
akashvibhute 0:30537dec6e0b 49 u_cone_sides.real = this->cone_sides;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset + 0) = (u_cone_sides.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset + 1) = (u_cone_sides.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset + 2) = (u_cone_sides.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 53 *(outbuffer + offset + 3) = (u_cone_sides.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 54 offset += sizeof(this->cone_sides);
akashvibhute 0:30537dec6e0b 55 offset += this->sensor_pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 56 offset += serializeAvrFloat64(outbuffer + offset, this->max_view_angle);
akashvibhute 0:30537dec6e0b 57 offset += serializeAvrFloat64(outbuffer + offset, this->max_range_angle);
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset + 0) = (this->sensor_view_direction >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 59 offset += sizeof(this->sensor_view_direction);
akashvibhute 0:30537dec6e0b 60 offset += serializeAvrFloat64(outbuffer + offset, this->weight);
akashvibhute 0:30537dec6e0b 61 return offset;
akashvibhute 0:30537dec6e0b 62 }
akashvibhute 0:30537dec6e0b 63
akashvibhute 0:30537dec6e0b 64 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 65 {
akashvibhute 0:30537dec6e0b 66 int offset = 0;
akashvibhute 0:30537dec6e0b 67 offset += deserializeAvrFloat64(inbuffer + offset, &(this->target_radius));
akashvibhute 0:30537dec6e0b 68 offset += this->target_pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 69 union {
akashvibhute 0:30537dec6e0b 70 int32_t real;
akashvibhute 0:30537dec6e0b 71 uint32_t base;
akashvibhute 0:30537dec6e0b 72 } u_cone_sides;
akashvibhute 0:30537dec6e0b 73 u_cone_sides.base = 0;
akashvibhute 0:30537dec6e0b 74 u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 75 u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 76 u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 77 u_cone_sides.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 78 this->cone_sides = u_cone_sides.real;
akashvibhute 0:30537dec6e0b 79 offset += sizeof(this->cone_sides);
akashvibhute 0:30537dec6e0b 80 offset += this->sensor_pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 81 offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_view_angle));
akashvibhute 0:30537dec6e0b 82 offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_range_angle));
akashvibhute 0:30537dec6e0b 83 this->sensor_view_direction = ((uint8_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 84 offset += sizeof(this->sensor_view_direction);
akashvibhute 0:30537dec6e0b 85 offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight));
akashvibhute 0:30537dec6e0b 86 return offset;
akashvibhute 0:30537dec6e0b 87 }
akashvibhute 0:30537dec6e0b 88
akashvibhute 0:30537dec6e0b 89 const char * getType(){ return "moveit_msgs/VisibilityConstraint"; };
akashvibhute 0:30537dec6e0b 90 const char * getMD5(){ return "62cda903bfe31ff2e5fcdc3810d577ad"; };
akashvibhute 0:30537dec6e0b 91
akashvibhute 0:30537dec6e0b 92 };
akashvibhute 0:30537dec6e0b 93
akashvibhute 0:30537dec6e0b 94 }
akashvibhute 0:30537dec6e0b 95 #endif