SetJointTrajectory.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_SetJointTrajectory_h
00002 #define _ROS_SERVICE_SetJointTrajectory_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "trajectory_msgs/JointTrajectory.h"
00008 #include "geometry_msgs/Pose.h"
00009 
00010 namespace gazebo_msgs
00011 {
00012 
00013 static const char SETJOINTTRAJECTORY[] = "gazebo_msgs/SetJointTrajectory";
00014 
00015   class SetJointTrajectoryRequest : public ros::Msg
00016   {
00017     public:
00018       char * model_name;
00019       trajectory_msgs::JointTrajectory joint_trajectory;
00020       geometry_msgs::Pose model_pose;
00021       bool set_model_pose;
00022       bool disable_physics_updates;
00023 
00024     virtual int serialize(unsigned char *outbuffer) const
00025     {
00026       int offset = 0;
00027       uint32_t length_model_name = strlen( (const char*) this->model_name);
00028       memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
00029       offset += 4;
00030       memcpy(outbuffer + offset, this->model_name, length_model_name);
00031       offset += length_model_name;
00032       offset += this->joint_trajectory.serialize(outbuffer + offset);
00033       offset += this->model_pose.serialize(outbuffer + offset);
00034       union {
00035         bool real;
00036         uint8_t base;
00037       } u_set_model_pose;
00038       u_set_model_pose.real = this->set_model_pose;
00039       *(outbuffer + offset + 0) = (u_set_model_pose.base >> (8 * 0)) & 0xFF;
00040       offset += sizeof(this->set_model_pose);
00041       union {
00042         bool real;
00043         uint8_t base;
00044       } u_disable_physics_updates;
00045       u_disable_physics_updates.real = this->disable_physics_updates;
00046       *(outbuffer + offset + 0) = (u_disable_physics_updates.base >> (8 * 0)) & 0xFF;
00047       offset += sizeof(this->disable_physics_updates);
00048       return offset;
00049     }
00050 
00051     virtual int deserialize(unsigned char *inbuffer)
00052     {
00053       int offset = 0;
00054       uint32_t length_model_name;
00055       memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
00056       offset += 4;
00057       for(unsigned int k= offset; k< offset+length_model_name; ++k){
00058           inbuffer[k-1]=inbuffer[k];
00059       }
00060       inbuffer[offset+length_model_name-1]=0;
00061       this->model_name = (char *)(inbuffer + offset-1);
00062       offset += length_model_name;
00063       offset += this->joint_trajectory.deserialize(inbuffer + offset);
00064       offset += this->model_pose.deserialize(inbuffer + offset);
00065       union {
00066         bool real;
00067         uint8_t base;
00068       } u_set_model_pose;
00069       u_set_model_pose.base = 0;
00070       u_set_model_pose.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00071       this->set_model_pose = u_set_model_pose.real;
00072       offset += sizeof(this->set_model_pose);
00073       union {
00074         bool real;
00075         uint8_t base;
00076       } u_disable_physics_updates;
00077       u_disable_physics_updates.base = 0;
00078       u_disable_physics_updates.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00079       this->disable_physics_updates = u_disable_physics_updates.real;
00080       offset += sizeof(this->disable_physics_updates);
00081      return offset;
00082     }
00083 
00084     const char * getType(){ return SETJOINTTRAJECTORY; };
00085     const char * getMD5(){ return "649dd2eba5ffd358069238825f9f85ab"; };
00086 
00087   };
00088 
00089   class SetJointTrajectoryResponse : public ros::Msg
00090   {
00091     public:
00092       bool success;
00093       char * status_message;
00094 
00095     virtual int serialize(unsigned char *outbuffer) const
00096     {
00097       int offset = 0;
00098       union {
00099         bool real;
00100         uint8_t base;
00101       } u_success;
00102       u_success.real = this->success;
00103       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
00104       offset += sizeof(this->success);
00105       uint32_t length_status_message = strlen( (const char*) this->status_message);
00106       memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
00107       offset += 4;
00108       memcpy(outbuffer + offset, this->status_message, length_status_message);
00109       offset += length_status_message;
00110       return offset;
00111     }
00112 
00113     virtual int deserialize(unsigned char *inbuffer)
00114     {
00115       int offset = 0;
00116       union {
00117         bool real;
00118         uint8_t base;
00119       } u_success;
00120       u_success.base = 0;
00121       u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00122       this->success = u_success.real;
00123       offset += sizeof(this->success);
00124       uint32_t length_status_message;
00125       memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
00126       offset += 4;
00127       for(unsigned int k= offset; k< offset+length_status_message; ++k){
00128           inbuffer[k-1]=inbuffer[k];
00129       }
00130       inbuffer[offset+length_status_message-1]=0;
00131       this->status_message = (char *)(inbuffer + offset-1);
00132       offset += length_status_message;
00133      return offset;
00134     }
00135 
00136     const char * getType(){ return SETJOINTTRAJECTORY; };
00137     const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
00138 
00139   };
00140 
00141   class SetJointTrajectory {
00142     public:
00143     typedef SetJointTrajectoryRequest Request;
00144     typedef SetJointTrajectoryResponse Response;
00145   };
00146 
00147 }
00148 #endif


lizi_arduino
Author(s): RoboTiCan
autogenerated on Wed Aug 26 2015 12:24:22