rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
moveit_msgs/PlaceLocation.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_moveit_msgs_PlaceLocation_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_PlaceLocation_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 "trajectory_msgs/JointTrajectory.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "geometry_msgs/PoseStamped.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/GripperTranslation.h" |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | namespace moveit_msgs |
akashvibhute | 0:30537dec6e0b | 13 | { |
akashvibhute | 0:30537dec6e0b | 14 | |
akashvibhute | 0:30537dec6e0b | 15 | class PlaceLocation : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 16 | { |
akashvibhute | 0:30537dec6e0b | 17 | public: |
akashvibhute | 0:30537dec6e0b | 18 | const char* id; |
akashvibhute | 0:30537dec6e0b | 19 | trajectory_msgs::JointTrajectory post_place_posture; |
akashvibhute | 0:30537dec6e0b | 20 | geometry_msgs::PoseStamped place_pose; |
akashvibhute | 0:30537dec6e0b | 21 | moveit_msgs::GripperTranslation pre_place_approach; |
akashvibhute | 0:30537dec6e0b | 22 | moveit_msgs::GripperTranslation post_place_retreat; |
akashvibhute | 0:30537dec6e0b | 23 | uint8_t allowed_touch_objects_length; |
akashvibhute | 0:30537dec6e0b | 24 | char* st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 25 | char* * allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 26 | |
akashvibhute | 0:30537dec6e0b | 27 | PlaceLocation(): |
akashvibhute | 0:30537dec6e0b | 28 | id(""), |
akashvibhute | 0:30537dec6e0b | 29 | post_place_posture(), |
akashvibhute | 0:30537dec6e0b | 30 | place_pose(), |
akashvibhute | 0:30537dec6e0b | 31 | pre_place_approach(), |
akashvibhute | 0:30537dec6e0b | 32 | post_place_retreat(), |
akashvibhute | 0:30537dec6e0b | 33 | allowed_touch_objects_length(0), allowed_touch_objects(NULL) |
akashvibhute | 0:30537dec6e0b | 34 | { |
akashvibhute | 0:30537dec6e0b | 35 | } |
akashvibhute | 0:30537dec6e0b | 36 | |
akashvibhute | 0:30537dec6e0b | 37 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 38 | { |
akashvibhute | 0:30537dec6e0b | 39 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 40 | uint32_t length_id = strlen(this->id); |
akashvibhute | 0:30537dec6e0b | 41 | memcpy(outbuffer + offset, &length_id, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 42 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 43 | memcpy(outbuffer + offset, this->id, length_id); |
akashvibhute | 0:30537dec6e0b | 44 | offset += length_id; |
akashvibhute | 0:30537dec6e0b | 45 | offset += this->post_place_posture.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 46 | offset += this->place_pose.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 47 | offset += this->pre_place_approach.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 48 | offset += this->post_place_retreat.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 49 | *(outbuffer + offset++) = allowed_touch_objects_length; |
akashvibhute | 0:30537dec6e0b | 50 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 51 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 52 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 53 | for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 54 | uint32_t length_allowed_touch_objectsi = strlen(this->allowed_touch_objects[i]); |
akashvibhute | 0:30537dec6e0b | 55 | memcpy(outbuffer + offset, &length_allowed_touch_objectsi, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 56 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 57 | memcpy(outbuffer + offset, this->allowed_touch_objects[i], length_allowed_touch_objectsi); |
akashvibhute | 0:30537dec6e0b | 58 | offset += length_allowed_touch_objectsi; |
akashvibhute | 0:30537dec6e0b | 59 | } |
akashvibhute | 0:30537dec6e0b | 60 | return offset; |
akashvibhute | 0:30537dec6e0b | 61 | } |
akashvibhute | 0:30537dec6e0b | 62 | |
akashvibhute | 0:30537dec6e0b | 63 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 64 | { |
akashvibhute | 0:30537dec6e0b | 65 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 66 | uint32_t length_id; |
akashvibhute | 0:30537dec6e0b | 67 | memcpy(&length_id, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 68 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 69 | for(unsigned int k= offset; k< offset+length_id; ++k){ |
akashvibhute | 0:30537dec6e0b | 70 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 71 | } |
akashvibhute | 0:30537dec6e0b | 72 | inbuffer[offset+length_id-1]=0; |
akashvibhute | 0:30537dec6e0b | 73 | this->id = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 74 | offset += length_id; |
akashvibhute | 0:30537dec6e0b | 75 | offset += this->post_place_posture.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 76 | offset += this->place_pose.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 77 | offset += this->pre_place_approach.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 78 | offset += this->post_place_retreat.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 79 | uint8_t allowed_touch_objects_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 80 | if(allowed_touch_objects_lengthT > allowed_touch_objects_length) |
akashvibhute | 0:30537dec6e0b | 81 | this->allowed_touch_objects = (char**)realloc(this->allowed_touch_objects, allowed_touch_objects_lengthT * sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 82 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 83 | allowed_touch_objects_length = allowed_touch_objects_lengthT; |
akashvibhute | 0:30537dec6e0b | 84 | for( uint8_t i = 0; i < allowed_touch_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 85 | uint32_t length_st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 86 | memcpy(&length_st_allowed_touch_objects, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 87 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 88 | for(unsigned int k= offset; k< offset+length_st_allowed_touch_objects; ++k){ |
akashvibhute | 0:30537dec6e0b | 89 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 90 | } |
akashvibhute | 0:30537dec6e0b | 91 | inbuffer[offset+length_st_allowed_touch_objects-1]=0; |
akashvibhute | 0:30537dec6e0b | 92 | this->st_allowed_touch_objects = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 93 | offset += length_st_allowed_touch_objects; |
akashvibhute | 0:30537dec6e0b | 94 | memcpy( &(this->allowed_touch_objects[i]), &(this->st_allowed_touch_objects), sizeof(char*)); |
akashvibhute | 0:30537dec6e0b | 95 | } |
akashvibhute | 0:30537dec6e0b | 96 | return offset; |
akashvibhute | 0:30537dec6e0b | 97 | } |
akashvibhute | 0:30537dec6e0b | 98 | |
akashvibhute | 0:30537dec6e0b | 99 | const char * getType(){ return "moveit_msgs/PlaceLocation"; }; |
akashvibhute | 0:30537dec6e0b | 100 | const char * getMD5(){ return "f3dbcaca40fb29ede2af78b3e1831128"; }; |
akashvibhute | 0:30537dec6e0b | 101 | |
akashvibhute | 0:30537dec6e0b | 102 | }; |
akashvibhute | 0:30537dec6e0b | 103 | |
akashvibhute | 0:30537dec6e0b | 104 | } |
akashvibhute | 0:30537dec6e0b | 105 | #endif |