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/RobotState.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_RobotState_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_moveit_msgs_RobotState_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/JointState.h" |
akashvibhute | 0:30537dec6e0b | 9 | #include "sensor_msgs/MultiDOFJointState.h" |
akashvibhute | 0:30537dec6e0b | 10 | #include "moveit_msgs/AttachedCollisionObject.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 RobotState : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 16 | { |
akashvibhute | 0:30537dec6e0b | 17 | public: |
akashvibhute | 0:30537dec6e0b | 18 | sensor_msgs::JointState joint_state; |
akashvibhute | 0:30537dec6e0b | 19 | sensor_msgs::MultiDOFJointState multi_dof_joint_state; |
akashvibhute | 0:30537dec6e0b | 20 | uint8_t attached_collision_objects_length; |
akashvibhute | 0:30537dec6e0b | 21 | moveit_msgs::AttachedCollisionObject st_attached_collision_objects; |
akashvibhute | 0:30537dec6e0b | 22 | moveit_msgs::AttachedCollisionObject * attached_collision_objects; |
akashvibhute | 0:30537dec6e0b | 23 | bool is_diff; |
akashvibhute | 0:30537dec6e0b | 24 | |
akashvibhute | 0:30537dec6e0b | 25 | RobotState(): |
akashvibhute | 0:30537dec6e0b | 26 | joint_state(), |
akashvibhute | 0:30537dec6e0b | 27 | multi_dof_joint_state(), |
akashvibhute | 0:30537dec6e0b | 28 | attached_collision_objects_length(0), attached_collision_objects(NULL), |
akashvibhute | 0:30537dec6e0b | 29 | is_diff(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->joint_state.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 37 | offset += this->multi_dof_joint_state.serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 38 | *(outbuffer + offset++) = attached_collision_objects_length; |
akashvibhute | 0:30537dec6e0b | 39 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 40 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 41 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 42 | for( uint8_t i = 0; i < attached_collision_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 43 | offset += this->attached_collision_objects[i].serialize(outbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 44 | } |
akashvibhute | 0:30537dec6e0b | 45 | union { |
akashvibhute | 0:30537dec6e0b | 46 | bool real; |
akashvibhute | 0:30537dec6e0b | 47 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 48 | } u_is_diff; |
akashvibhute | 0:30537dec6e0b | 49 | u_is_diff.real = this->is_diff; |
akashvibhute | 0:30537dec6e0b | 50 | *(outbuffer + offset + 0) = (u_is_diff.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 51 | offset += sizeof(this->is_diff); |
akashvibhute | 0:30537dec6e0b | 52 | return offset; |
akashvibhute | 0:30537dec6e0b | 53 | } |
akashvibhute | 0:30537dec6e0b | 54 | |
akashvibhute | 0:30537dec6e0b | 55 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 56 | { |
akashvibhute | 0:30537dec6e0b | 57 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 58 | offset += this->joint_state.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 59 | offset += this->multi_dof_joint_state.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 60 | uint8_t attached_collision_objects_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 61 | if(attached_collision_objects_lengthT > attached_collision_objects_length) |
akashvibhute | 0:30537dec6e0b | 62 | this->attached_collision_objects = (moveit_msgs::AttachedCollisionObject*)realloc(this->attached_collision_objects, attached_collision_objects_lengthT * sizeof(moveit_msgs::AttachedCollisionObject)); |
akashvibhute | 0:30537dec6e0b | 63 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 64 | attached_collision_objects_length = attached_collision_objects_lengthT; |
akashvibhute | 0:30537dec6e0b | 65 | for( uint8_t i = 0; i < attached_collision_objects_length; i++){ |
akashvibhute | 0:30537dec6e0b | 66 | offset += this->st_attached_collision_objects.deserialize(inbuffer + offset); |
akashvibhute | 0:30537dec6e0b | 67 | memcpy( &(this->attached_collision_objects[i]), &(this->st_attached_collision_objects), sizeof(moveit_msgs::AttachedCollisionObject)); |
akashvibhute | 0:30537dec6e0b | 68 | } |
akashvibhute | 0:30537dec6e0b | 69 | union { |
akashvibhute | 0:30537dec6e0b | 70 | bool real; |
akashvibhute | 0:30537dec6e0b | 71 | uint8_t base; |
akashvibhute | 0:30537dec6e0b | 72 | } u_is_diff; |
akashvibhute | 0:30537dec6e0b | 73 | u_is_diff.base = 0; |
akashvibhute | 0:30537dec6e0b | 74 | u_is_diff.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 75 | this->is_diff = u_is_diff.real; |
akashvibhute | 0:30537dec6e0b | 76 | offset += sizeof(this->is_diff); |
akashvibhute | 0:30537dec6e0b | 77 | return offset; |
akashvibhute | 0:30537dec6e0b | 78 | } |
akashvibhute | 0:30537dec6e0b | 79 | |
akashvibhute | 0:30537dec6e0b | 80 | const char * getType(){ return "moveit_msgs/RobotState"; }; |
akashvibhute | 0:30537dec6e0b | 81 | const char * getMD5(){ return "217a2e8e5547f4162b13a37db9cb4da4"; }; |
akashvibhute | 0:30537dec6e0b | 82 | |
akashvibhute | 0:30537dec6e0b | 83 | }; |
akashvibhute | 0:30537dec6e0b | 84 | |
akashvibhute | 0:30537dec6e0b | 85 | } |
akashvibhute | 0:30537dec6e0b | 86 | #endif |