1 #ifndef _ROS_sensor_msgs_MultiDOFJointState_h
2 #define _ROS_sensor_msgs_MultiDOFJointState_h
42 virtual int serialize(
unsigned char *outbuffer)
const
47 *(outbuffer + offset++) = 0;
48 *(outbuffer + offset++) = 0;
49 *(outbuffer + offset++) = 0;
51 uint32_t length_joint_namesi = strlen(this->
joint_names[i]);
52 memcpy(outbuffer + offset, &length_joint_namesi,
sizeof(uint32_t));
54 memcpy(outbuffer + offset, this->
joint_names[i], length_joint_namesi);
55 offset += length_joint_namesi;
58 *(outbuffer + offset++) = 0;
59 *(outbuffer + offset++) = 0;
60 *(outbuffer + offset++) = 0;
65 *(outbuffer + offset++) = 0;
66 *(outbuffer + offset++) = 0;
67 *(outbuffer + offset++) = 0;
72 *(outbuffer + offset++) = 0;
73 *(outbuffer + offset++) = 0;
74 *(outbuffer + offset++) = 0;
85 uint8_t joint_names_lengthT = *(inbuffer + offset++);
91 uint32_t length_st_joint_names;
92 memcpy(&length_st_joint_names, (inbuffer + offset),
sizeof(uint32_t));
94 for(
unsigned int k= offset; k< offset+length_st_joint_names; ++k){
95 inbuffer[k-1]=inbuffer[k];
97 inbuffer[offset+length_st_joint_names-1]=0;
99 offset += length_st_joint_names;
102 uint8_t transforms_lengthT = *(inbuffer + offset++);
111 uint8_t twist_lengthT = *(inbuffer + offset++);
120 uint8_t wrench_lengthT = *(inbuffer + offset++);
132 const char *
getType(){
return "sensor_msgs/MultiDOFJointState"; };
133 const char *
getMD5(){
return "690f272f0640d2631c305eeb8301e59d"; };
geometry_msgs::Twist st_twist
Definition: MultiDOFJointState.h:27
virtual int serialize(unsigned char *outbuffer) const
Definition: MultiDOFJointState.h:42
uint8_t twist_length
Definition: MultiDOFJointState.h:26
virtual int deserialize(unsigned char *inbuffer)
Definition: Twist.h:33
virtual int deserialize(unsigned char *inbuffer)
Definition: MultiDOFJointState.h:81
geometry_msgs::Twist * twist
Definition: MultiDOFJointState.h:28
uint8_t transforms_length
Definition: MultiDOFJointState.h:23
virtual int serialize(unsigned char *outbuffer) const
Definition: Twist.h:25
geometry_msgs::Wrench * wrench
Definition: MultiDOFJointState.h:31
uint8_t wrench_length
Definition: MultiDOFJointState.h:29
uint8_t joint_names_length
Definition: MultiDOFJointState.h:20
MultiDOFJointState()
Definition: MultiDOFJointState.h:33
std_msgs::Header header
Definition: MultiDOFJointState.h:19
geometry_msgs::Wrench st_wrench
Definition: MultiDOFJointState.h:30
Definition: MultiDOFJointState.h:16
virtual int deserialize(unsigned char *inbuffer)
Definition: Wrench.h:33
const char * getType()
Definition: MultiDOFJointState.h:132
virtual int serialize(unsigned char *outbuffer) const
Definition: Wrench.h:25
geometry_msgs::Transform * transforms
Definition: MultiDOFJointState.h:25
char * st_joint_names
Definition: MultiDOFJointState.h:21
geometry_msgs::Transform st_transforms
Definition: MultiDOFJointState.h:24
char ** joint_names
Definition: MultiDOFJointState.h:22
const char * getMD5()
Definition: MultiDOFJointState.h:133