rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
manipulation_msgs/SceneRegion.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_manipulation_msgs_SceneRegion_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_manipulation_msgs_SceneRegion_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 "sensor_msgs/PointCloud2.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "sensor_msgs/Image.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "sensor_msgs/CameraInfo.h" |
akashvibhute | 0:30537dec6e0b | 11 | #include "geometry_msgs/PoseStamped.h" |
akashvibhute | 0:30537dec6e0b | 12 | #include "geometry_msgs/Vector3.h" |
akashvibhute | 0:30537dec6e0b | 13 | |
akashvibhute | 0:30537dec6e0b | 14 | namespace manipulation_msgs |
akashvibhute | 0:30537dec6e0b | 15 | { |
akashvibhute | 0:30537dec6e0b | 16 | |
akashvibhute | 0:30537dec6e0b | 17 | class SceneRegion : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 18 | { |
akashvibhute | 0:30537dec6e0b | 19 | public: |
akashvibhute | 0:30537dec6e0b | 20 | sensor_msgs::PointCloud2 cloud; |
akashvibhute | 0:30537dec6e0b | 21 | uint8_t mask_length; |
akashvibhute | 0:30537dec6e0b | 22 | int32_t st_mask; |
akashvibhute | 0:30537dec6e0b | 23 | int32_t * mask; |
akashvibhute | 0:30537dec6e0b | 24 | sensor_msgs::Image image; |
akashvibhute | 0:30537dec6e0b | 25 | sensor_msgs::Image disparity_image; |
akashvibhute | 0:30537dec6e0b | 26 | sensor_msgs::CameraInfo cam_info; |
akashvibhute | 0:30537dec6e0b | 27 | geometry_msgs::PoseStamped roi_box_pose; |
akashvibhute | 0:30537dec6e0b | 28 | geometry_msgs::Vector3 roi_box_dims; |
akashvibhute | 0:30537dec6e0b | 29 | |
akashvibhute | 0:30537dec6e0b | 30 | SceneRegion(): |
akashvibhute | 0:30537dec6e0b | 31 | cloud(), |
akashvibhute | 0:30537dec6e0b | 32 | mask_length(0), mask(NULL), |
akashvibhute | 0:30537dec6e0b | 33 | image(), |
akashvibhute | 0:30537dec6e0b | 34 | disparity_image(), |
akashvibhute | 0:30537dec6e0b | 35 | cam_info(), |
akashvibhute | 0:30537dec6e0b | 36 | roi_box_pose(), |
akashvibhute | 0:30537dec6e0b | 37 | roi_box_dims() |
akashvibhute | 0:30537dec6e0b | 38 | { |
akashvibhute | 0:30537dec6e0b | 39 | } |
akashvibhute | 0:30537dec6e0b | 40 | |
akashvibhute | 0:30537dec6e0b | 41 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 42 | { |
akashvibhute | 0:30537dec6e0b | 43 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 44 | offset += this->cloud.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 45 | *(outbuffer + offset++) = mask_length; |
akashvibhute | 0:30537dec6e0b | 46 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 47 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 48 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 49 | for( uint8_t i = 0; i < mask_length; i++){ |
akashvibhute | 0:30537dec6e0b | 50 | union { |
akashvibhute | 0:30537dec6e0b | 51 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 52 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 53 | } u_maski; |
akashvibhute | 0:30537dec6e0b | 54 | u_maski.real = this->mask[i]; |
akashvibhute | 0:30537dec6e0b | 55 | *(outbuffer + offset + 0) = (u_maski.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 56 | *(outbuffer + offset + 1) = (u_maski.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 57 | *(outbuffer + offset + 2) = (u_maski.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 58 | *(outbuffer + offset + 3) = (u_maski.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 59 | offset += sizeof(this->mask[i]); |
akashvibhute | 0:30537dec6e0b | 60 | } |
akashvibhute | 0:30537dec6e0b | 61 | offset += this->image.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 62 | offset += this->disparity_image.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 63 | offset += this->cam_info.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 64 | offset += this->roi_box_pose.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 65 | offset += this->roi_box_dims.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 66 | return offset; |
akashvibhute | 0:30537dec6e0b | 67 | } |
akashvibhute | 0:30537dec6e0b | 68 | |
akashvibhute | 0:30537dec6e0b | 69 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 70 | { |
akashvibhute | 0:30537dec6e0b | 71 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 72 | offset += this->cloud.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 73 | uint8_t mask_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 74 | if(mask_lengthT > mask_length) |
akashvibhute | 0:30537dec6e0b | 75 | this->mask = (int32_t*)realloc(this->mask, mask_lengthT * sizeof(int32_t)); |
akashvibhute | 0:30537dec6e0b | 76 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 77 | mask_length = mask_lengthT; |
akashvibhute | 0:30537dec6e0b | 78 | for( uint8_t i = 0; i < mask_length; i++){ |
akashvibhute | 0:30537dec6e0b | 79 | union { |
akashvibhute | 0:30537dec6e0b | 80 | int32_t real; |
akashvibhute | 0:30537dec6e0b | 81 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 82 | } u_st_mask; |
akashvibhute | 0:30537dec6e0b | 83 | u_st_mask.base = 0; |
akashvibhute | 0:30537dec6e0b | 84 | u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 85 | u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 86 | u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 87 | u_st_mask.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 88 | this->st_mask = u_st_mask.real; |
akashvibhute | 0:30537dec6e0b | 89 | offset += sizeof(this->st_mask); |
akashvibhute | 0:30537dec6e0b | 90 | memcpy( &(this->mask[i]), &(this->st_mask), sizeof(int32_t)); |
akashvibhute | 0:30537dec6e0b | 91 | } |
akashvibhute | 0:30537dec6e0b | 92 | offset += this->image.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 93 | offset += this->disparity_image.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 94 | offset += this->cam_info.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 95 | offset += this->roi_box_pose.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 96 | offset += this->roi_box_dims.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 97 | return offset; |
akashvibhute | 0:30537dec6e0b | 98 | } |
akashvibhute | 0:30537dec6e0b | 99 | |
akashvibhute | 0:30537dec6e0b | 100 | const char * getType(){ return "manipulation_msgs/SceneRegion"; }; |
akashvibhute | 0:30537dec6e0b | 101 | const char * getMD5(){ return "0a9ab02b19292633619876c9d247690c"; }; |
akashvibhute | 0:30537dec6e0b | 102 | |
akashvibhute | 0:30537dec6e0b | 103 | }; |
akashvibhute | 0:30537dec6e0b | 104 | |
akashvibhute | 0:30537dec6e0b | 105 | } |
akashvibhute | 0:30537dec6e0b | 106 | #endif |