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/Constraints.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_Constraints_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_Constraints_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 "moveit_msgs/JointConstraint.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "moveit_msgs/PositionConstraint.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/OrientationConstraint.h" |
akashvibhute | 0:30537dec6e0b | 11 | #include "moveit_msgs/VisibilityConstraint.h" |
akashvibhute | 0:30537dec6e0b | 12 | |
akashvibhute | 0:30537dec6e0b | 13 | namespace moveit_msgs |
akashvibhute | 0:30537dec6e0b | 14 | { |
akashvibhute | 0:30537dec6e0b | 15 | |
akashvibhute | 0:30537dec6e0b | 16 | class Constraints : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 17 | { |
akashvibhute | 0:30537dec6e0b | 18 | public: |
akashvibhute | 0:30537dec6e0b | 19 | const char* name; |
akashvibhute | 0:30537dec6e0b | 20 | uint8_t joint_constraints_length; |
akashvibhute | 0:30537dec6e0b | 21 | moveit_msgs::JointConstraint st_joint_constraints; |
akashvibhute | 0:30537dec6e0b | 22 | moveit_msgs::JointConstraint * joint_constraints; |
akashvibhute | 0:30537dec6e0b | 23 | uint8_t position_constraints_length; |
akashvibhute | 0:30537dec6e0b | 24 | moveit_msgs::PositionConstraint st_position_constraints; |
akashvibhute | 0:30537dec6e0b | 25 | moveit_msgs::PositionConstraint * position_constraints; |
akashvibhute | 0:30537dec6e0b | 26 | uint8_t orientation_constraints_length; |
akashvibhute | 0:30537dec6e0b | 27 | moveit_msgs::OrientationConstraint st_orientation_constraints; |
akashvibhute | 0:30537dec6e0b | 28 | moveit_msgs::OrientationConstraint * orientation_constraints; |
akashvibhute | 0:30537dec6e0b | 29 | uint8_t visibility_constraints_length; |
akashvibhute | 0:30537dec6e0b | 30 | moveit_msgs::VisibilityConstraint st_visibility_constraints; |
akashvibhute | 0:30537dec6e0b | 31 | moveit_msgs::VisibilityConstraint * visibility_constraints; |
akashvibhute | 0:30537dec6e0b | 32 | |
akashvibhute | 0:30537dec6e0b | 33 | Constraints(): |
akashvibhute | 0:30537dec6e0b | 34 | name(""), |
akashvibhute | 0:30537dec6e0b | 35 | joint_constraints_length(0), joint_constraints(NULL), |
akashvibhute | 0:30537dec6e0b | 36 | position_constraints_length(0), position_constraints(NULL), |
akashvibhute | 0:30537dec6e0b | 37 | orientation_constraints_length(0), orientation_constraints(NULL), |
akashvibhute | 0:30537dec6e0b | 38 | visibility_constraints_length(0), visibility_constraints(NULL) |
akashvibhute | 0:30537dec6e0b | 39 | { |
akashvibhute | 0:30537dec6e0b | 40 | } |
akashvibhute | 0:30537dec6e0b | 41 | |
akashvibhute | 0:30537dec6e0b | 42 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 43 | { |
akashvibhute | 0:30537dec6e0b | 44 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 45 | uint32_t length_name = strlen(this->name); |
akashvibhute | 0:30537dec6e0b | 46 | memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 47 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 48 | memcpy(outbuffer + offset, this->name, length_name); |
akashvibhute | 0:30537dec6e0b | 49 | offset += length_name; |
akashvibhute | 0:30537dec6e0b | 50 | *(outbuffer + offset++) = joint_constraints_length; |
akashvibhute | 0:30537dec6e0b | 51 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 52 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 53 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 54 | for( uint8_t i = 0; i < joint_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 55 | offset += this->joint_constraints[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 56 | } |
akashvibhute | 0:30537dec6e0b | 57 | *(outbuffer + offset++) = position_constraints_length; |
akashvibhute | 0:30537dec6e0b | 58 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 59 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 60 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 61 | for( uint8_t i = 0; i < position_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 62 | offset += this->position_constraints[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 63 | } |
akashvibhute | 0:30537dec6e0b | 64 | *(outbuffer + offset++) = orientation_constraints_length; |
akashvibhute | 0:30537dec6e0b | 65 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 66 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 67 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 68 | for( uint8_t i = 0; i < orientation_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 69 | offset += this->orientation_constraints[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 70 | } |
akashvibhute | 0:30537dec6e0b | 71 | *(outbuffer + offset++) = visibility_constraints_length; |
akashvibhute | 0:30537dec6e0b | 72 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 73 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 74 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 75 | for( uint8_t i = 0; i < visibility_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 76 | offset += this->visibility_constraints[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 77 | } |
akashvibhute | 0:30537dec6e0b | 78 | return offset; |
akashvibhute | 0:30537dec6e0b | 79 | } |
akashvibhute | 0:30537dec6e0b | 80 | |
akashvibhute | 0:30537dec6e0b | 81 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 82 | { |
akashvibhute | 0:30537dec6e0b | 83 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 84 | uint32_t length_name; |
akashvibhute | 0:30537dec6e0b | 85 | memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); |
akashvibhute | 0:30537dec6e0b | 86 | offset += 4; |
akashvibhute | 0:30537dec6e0b | 87 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
akashvibhute | 0:30537dec6e0b | 88 | inbuffer[k-1]=inbuffer[k]; |
akashvibhute | 0:30537dec6e0b | 89 | } |
akashvibhute | 0:30537dec6e0b | 90 | inbuffer[offset+length_name-1]=0; |
akashvibhute | 0:30537dec6e0b | 91 | this->name = (char *)(inbuffer + offset-1); |
akashvibhute | 0:30537dec6e0b | 92 | offset += length_name; |
akashvibhute | 0:30537dec6e0b | 93 | uint8_t joint_constraints_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 94 | if(joint_constraints_lengthT > joint_constraints_length) |
akashvibhute | 0:30537dec6e0b | 95 | this->joint_constraints = (moveit_msgs::JointConstraint*)realloc(this->joint_constraints, joint_constraints_lengthT * sizeof(moveit_msgs::JointConstraint)); |
akashvibhute | 0:30537dec6e0b | 96 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 97 | joint_constraints_length = joint_constraints_lengthT; |
akashvibhute | 0:30537dec6e0b | 98 | for( uint8_t i = 0; i < joint_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 99 | offset += this->st_joint_constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 100 | memcpy( &(this->joint_constraints[i]), &(this->st_joint_constraints), sizeof(moveit_msgs::JointConstraint)); |
akashvibhute | 0:30537dec6e0b | 101 | } |
akashvibhute | 0:30537dec6e0b | 102 | uint8_t position_constraints_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 103 | if(position_constraints_lengthT > position_constraints_length) |
akashvibhute | 0:30537dec6e0b | 104 | this->position_constraints = (moveit_msgs::PositionConstraint*)realloc(this->position_constraints, position_constraints_lengthT * sizeof(moveit_msgs::PositionConstraint)); |
akashvibhute | 0:30537dec6e0b | 105 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 106 | position_constraints_length = position_constraints_lengthT; |
akashvibhute | 0:30537dec6e0b | 107 | for( uint8_t i = 0; i < position_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 108 | offset += this->st_position_constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 109 | memcpy( &(this->position_constraints[i]), &(this->st_position_constraints), sizeof(moveit_msgs::PositionConstraint)); |
akashvibhute | 0:30537dec6e0b | 110 | } |
akashvibhute | 0:30537dec6e0b | 111 | uint8_t orientation_constraints_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 112 | if(orientation_constraints_lengthT > orientation_constraints_length) |
akashvibhute | 0:30537dec6e0b | 113 | this->orientation_constraints = (moveit_msgs::OrientationConstraint*)realloc(this->orientation_constraints, orientation_constraints_lengthT * sizeof(moveit_msgs::OrientationConstraint)); |
akashvibhute | 0:30537dec6e0b | 114 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 115 | orientation_constraints_length = orientation_constraints_lengthT; |
akashvibhute | 0:30537dec6e0b | 116 | for( uint8_t i = 0; i < orientation_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 117 | offset += this->st_orientation_constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 118 | memcpy( &(this->orientation_constraints[i]), &(this->st_orientation_constraints), sizeof(moveit_msgs::OrientationConstraint)); |
akashvibhute | 0:30537dec6e0b | 119 | } |
akashvibhute | 0:30537dec6e0b | 120 | uint8_t visibility_constraints_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 121 | if(visibility_constraints_lengthT > visibility_constraints_length) |
akashvibhute | 0:30537dec6e0b | 122 | this->visibility_constraints = (moveit_msgs::VisibilityConstraint*)realloc(this->visibility_constraints, visibility_constraints_lengthT * sizeof(moveit_msgs::VisibilityConstraint)); |
akashvibhute | 0:30537dec6e0b | 123 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 124 | visibility_constraints_length = visibility_constraints_lengthT; |
akashvibhute | 0:30537dec6e0b | 125 | for( uint8_t i = 0; i < visibility_constraints_length; i++){ |
akashvibhute | 0:30537dec6e0b | 126 | offset += this->st_visibility_constraints.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 127 | memcpy( &(this->visibility_constraints[i]), &(this->st_visibility_constraints), sizeof(moveit_msgs::VisibilityConstraint)); |
akashvibhute | 0:30537dec6e0b | 128 | } |
akashvibhute | 0:30537dec6e0b | 129 | return offset; |
akashvibhute | 0:30537dec6e0b | 130 | } |
akashvibhute | 0:30537dec6e0b | 131 | |
akashvibhute | 0:30537dec6e0b | 132 | const char * getType(){ return "moveit_msgs/Constraints"; }; |
akashvibhute | 0:30537dec6e0b | 133 | const char * getMD5(){ return "8d5ce8d34ef26c65fb5d43c9e99bf6e0"; }; |
akashvibhute | 0:30537dec6e0b | 134 | |
akashvibhute | 0:30537dec6e0b | 135 | }; |
akashvibhute | 0:30537dec6e0b | 136 | |
akashvibhute | 0:30537dec6e0b | 137 | } |
akashvibhute | 0:30537dec6e0b | 138 | #endif |