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/PositionConstraint.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_PositionConstraint_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_PositionConstraint_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 "std_msgs/Header.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "geometry_msgs/Vector3.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/BoundingVolume.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 PositionConstraint : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 16 | { |
akashvibhute | 0:30537dec6e0b | 17 | public: |
akashvibhute | 0:30537dec6e0b | 18 | std_msgs::Header header; |
akashvibhute | 0:30537dec6e0b | 19 | const char* link_name; |
akashvibhute | 0:30537dec6e0b | 20 | geometry_msgs::Vector3 target_point_offset; |
akashvibhute | 0:30537dec6e0b | 21 | moveit_msgs::BoundingVolume constraint_region; |
akashvibhute | 0:30537dec6e0b | 22 | float weight; |
akashvibhute | 0:30537dec6e0b | 23 | |
akashvibhute | 0:30537dec6e0b | 24 | PositionConstraint(): |
akashvibhute | 0:30537dec6e0b | 25 | header(), |
akashvibhute | 0:30537dec6e0b | 26 | link_name(""), |
akashvibhute | 0:30537dec6e0b | 27 | target_point_offset(), |
akashvibhute | 0:30537dec6e0b | 28 | constraint_region(), |
akashvibhute | 0:30537dec6e0b | 29 | weight(0) |
akashvibhute | 0:30537dec6e0b | 30 | { |
akashvibhute | 0:30537dec6e0b | 31 | } |
akashvibhute | 0:30537dec6e0b | 32 | |
akashvibhute | 0:30537dec6e0b | 33 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 34 | { |
akashvibhute | 0:30537dec6e0b | 35 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 36 | offset += this->header.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 37 | uint32_t length_link_name = strlen(this->link_name); |
akashvibhute | 0:30537dec6e0b | 38 | memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 39 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 40 | memcpy(outbuffer + offset, this->link_name, length_link_name); |
akashvibhute | 0:30537dec6e0b | 41 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 42 | offset += this->target_point_offset.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 43 | offset += this->constraint_region.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 44 | offset += serializeAvrFloat64(outbuffer + offset, this->weight); |
akashvibhute | 0:30537dec6e0b | 45 | return offset; |
akashvibhute | 0:30537dec6e0b | 46 | } |
akashvibhute | 0:30537dec6e0b | 47 | |
akashvibhute | 0:30537dec6e0b | 48 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 49 | { |
akashvibhute | 0:30537dec6e0b | 50 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 51 | offset += this->header.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 52 | uint32_t length_link_name; |
akashvibhute | 0:30537dec6e0b | 53 | memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 54 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 55 | for(unsigned int k= offset; k< offset+length_link_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 56 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 57 | } |
akashvibhute | 0:30537dec6e0b | 58 | inbuffer[offset+length_link_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 59 | this->link_name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 60 | offset += length_link_name; |
akashvibhute | 0:30537dec6e0b | 61 | offset += this->target_point_offset.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 62 | offset += this->constraint_region.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 63 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight)); |
akashvibhute | 0:30537dec6e0b | 64 | return offset; |
akashvibhute | 0:30537dec6e0b | 65 | } |
akashvibhute | 0:30537dec6e0b | 66 | |
akashvibhute | 0:30537dec6e0b | 67 | const char * getType(){ return "moveit_msgs/PositionConstraint"; }; |
akashvibhute | 0:30537dec6e0b | 68 | const char * getMD5(){ return "c83edf208d87d3aa3169f47775a58e6a"; }; |
akashvibhute | 0:30537dec6e0b | 69 | |
akashvibhute | 0:30537dec6e0b | 70 | }; |
akashvibhute | 0:30537dec6e0b | 71 | |
akashvibhute | 0:30537dec6e0b | 72 | } |
akashvibhute | 0:30537dec6e0b | 73 | #endif |