Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
RobotState.h
00001 #ifndef _ROS_moveit_msgs_RobotState_h 00002 #define _ROS_moveit_msgs_RobotState_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "sensor_msgs/JointState.h" 00009 #include "sensor_msgs/MultiDOFJointState.h" 00010 #include "moveit_msgs/AttachedCollisionObject.h" 00011 00012 namespace moveit_msgs 00013 { 00014 00015 class RobotState : public ros::Msg 00016 { 00017 public: 00018 typedef sensor_msgs::JointState _joint_state_type; 00019 _joint_state_type joint_state; 00020 typedef sensor_msgs::MultiDOFJointState _multi_dof_joint_state_type; 00021 _multi_dof_joint_state_type multi_dof_joint_state; 00022 uint32_t attached_collision_objects_length; 00023 typedef moveit_msgs::AttachedCollisionObject _attached_collision_objects_type; 00024 _attached_collision_objects_type st_attached_collision_objects; 00025 _attached_collision_objects_type * attached_collision_objects; 00026 typedef bool _is_diff_type; 00027 _is_diff_type is_diff; 00028 00029 RobotState(): 00030 joint_state(), 00031 multi_dof_joint_state(), 00032 attached_collision_objects_length(0), attached_collision_objects(NULL), 00033 is_diff(0) 00034 { 00035 } 00036 00037 virtual int serialize(unsigned char *outbuffer) const 00038 { 00039 int offset = 0; 00040 offset += this->joint_state.serialize(outbuffer + offset); 00041 offset += this->multi_dof_joint_state.serialize(outbuffer + offset); 00042 *(outbuffer + offset + 0) = (this->attached_collision_objects_length >> (8 * 0)) & 0xFF; 00043 *(outbuffer + offset + 1) = (this->attached_collision_objects_length >> (8 * 1)) & 0xFF; 00044 *(outbuffer + offset + 2) = (this->attached_collision_objects_length >> (8 * 2)) & 0xFF; 00045 *(outbuffer + offset + 3) = (this->attached_collision_objects_length >> (8 * 3)) & 0xFF; 00046 offset += sizeof(this->attached_collision_objects_length); 00047 for( uint32_t i = 0; i < attached_collision_objects_length; i++){ 00048 offset += this->attached_collision_objects[i].serialize(outbuffer + offset); 00049 } 00050 union { 00051 bool real; 00052 uint8_t base; 00053 } u_is_diff; 00054 u_is_diff.real = this->is_diff; 00055 *(outbuffer + offset + 0) = (u_is_diff.base >> (8 * 0)) & 0xFF; 00056 offset += sizeof(this->is_diff); 00057 return offset; 00058 } 00059 00060 virtual int deserialize(unsigned char *inbuffer) 00061 { 00062 int offset = 0; 00063 offset += this->joint_state.deserialize(inbuffer + offset); 00064 offset += this->multi_dof_joint_state.deserialize(inbuffer + offset); 00065 uint32_t attached_collision_objects_lengthT = ((uint32_t) (*(inbuffer + offset))); 00066 attached_collision_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00067 attached_collision_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00068 attached_collision_objects_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00069 offset += sizeof(this->attached_collision_objects_length); 00070 if(attached_collision_objects_lengthT > attached_collision_objects_length) 00071 this->attached_collision_objects = (moveit_msgs::AttachedCollisionObject*)realloc(this->attached_collision_objects, attached_collision_objects_lengthT * sizeof(moveit_msgs::AttachedCollisionObject)); 00072 attached_collision_objects_length = attached_collision_objects_lengthT; 00073 for( uint32_t i = 0; i < attached_collision_objects_length; i++){ 00074 offset += this->st_attached_collision_objects.deserialize(inbuffer + offset); 00075 memcpy( &(this->attached_collision_objects[i]), &(this->st_attached_collision_objects), sizeof(moveit_msgs::AttachedCollisionObject)); 00076 } 00077 union { 00078 bool real; 00079 uint8_t base; 00080 } u_is_diff; 00081 u_is_diff.base = 0; 00082 u_is_diff.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00083 this->is_diff = u_is_diff.real; 00084 offset += sizeof(this->is_diff); 00085 return offset; 00086 } 00087 00088 virtual const char * getType(){ return "moveit_msgs/RobotState"; }; 00089 virtual const char * getMD5(){ return "217a2e8e5547f4162b13a37db9cb4da4"; }; 00090 00091 }; 00092 00093 } 00094 #endif
Generated on Mon Sep 26 2022 13:47:03 by
