Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Committer:
sgrsn
Date:
Mon Nov 02 09:00:01 2020 +0000
Revision:
2:5d429be7d0aa
Parent:
0:04ac6be8229a
Change INPUT_SIZE and OUTPUT_SIZE on node_handle.h to pub sub

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_trajectory_msgs_MultiDOFJointTrajectory_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "std_msgs/Header.h"
Gary Servin 0:04ac6be8229a 9 #include "trajectory_msgs/MultiDOFJointTrajectoryPoint.h"
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 namespace trajectory_msgs
Gary Servin 0:04ac6be8229a 12 {
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class MultiDOFJointTrajectory : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef std_msgs::Header _header_type;
Gary Servin 0:04ac6be8229a 18 _header_type header;
Gary Servin 0:04ac6be8229a 19 uint32_t joint_names_length;
Gary Servin 0:04ac6be8229a 20 typedef char* _joint_names_type;
Gary Servin 0:04ac6be8229a 21 _joint_names_type st_joint_names;
Gary Servin 0:04ac6be8229a 22 _joint_names_type * joint_names;
Gary Servin 0:04ac6be8229a 23 uint32_t points_length;
Gary Servin 0:04ac6be8229a 24 typedef trajectory_msgs::MultiDOFJointTrajectoryPoint _points_type;
Gary Servin 0:04ac6be8229a 25 _points_type st_points;
Gary Servin 0:04ac6be8229a 26 _points_type * points;
Gary Servin 0:04ac6be8229a 27
Gary Servin 0:04ac6be8229a 28 MultiDOFJointTrajectory():
Gary Servin 0:04ac6be8229a 29 header(),
Gary Servin 0:04ac6be8229a 30 joint_names_length(0), joint_names(NULL),
Gary Servin 0:04ac6be8229a 31 points_length(0), points(NULL)
Gary Servin 0:04ac6be8229a 32 {
Gary Servin 0:04ac6be8229a 33 }
Gary Servin 0:04ac6be8229a 34
Gary Servin 0:04ac6be8229a 35 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 36 {
Gary Servin 0:04ac6be8229a 37 int offset = 0;
Gary Servin 0:04ac6be8229a 38 offset += this->header.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 39 *(outbuffer + offset + 0) = (this->joint_names_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 40 *(outbuffer + offset + 1) = (this->joint_names_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 41 *(outbuffer + offset + 2) = (this->joint_names_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 42 *(outbuffer + offset + 3) = (this->joint_names_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 43 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 44 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 45 uint32_t length_joint_namesi = strlen(this->joint_names[i]);
Gary Servin 0:04ac6be8229a 46 varToArr(outbuffer + offset, length_joint_namesi);
Gary Servin 0:04ac6be8229a 47 offset += 4;
Gary Servin 0:04ac6be8229a 48 memcpy(outbuffer + offset, this->joint_names[i], length_joint_namesi);
Gary Servin 0:04ac6be8229a 49 offset += length_joint_namesi;
Gary Servin 0:04ac6be8229a 50 }
Gary Servin 0:04ac6be8229a 51 *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 52 *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 53 *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 54 *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 55 offset += sizeof(this->points_length);
Gary Servin 0:04ac6be8229a 56 for( uint32_t i = 0; i < points_length; i++){
Gary Servin 0:04ac6be8229a 57 offset += this->points[i].serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 58 }
Gary Servin 0:04ac6be8229a 59 return offset;
Gary Servin 0:04ac6be8229a 60 }
Gary Servin 0:04ac6be8229a 61
Gary Servin 0:04ac6be8229a 62 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 63 {
Gary Servin 0:04ac6be8229a 64 int offset = 0;
Gary Servin 0:04ac6be8229a 65 offset += this->header.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 66 uint32_t joint_names_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 67 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 68 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 69 joint_names_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 70 offset += sizeof(this->joint_names_length);
Gary Servin 0:04ac6be8229a 71 if(joint_names_lengthT > joint_names_length)
Gary Servin 0:04ac6be8229a 72 this->joint_names = (char**)realloc(this->joint_names, joint_names_lengthT * sizeof(char*));
Gary Servin 0:04ac6be8229a 73 joint_names_length = joint_names_lengthT;
Gary Servin 0:04ac6be8229a 74 for( uint32_t i = 0; i < joint_names_length; i++){
Gary Servin 0:04ac6be8229a 75 uint32_t length_st_joint_names;
Gary Servin 0:04ac6be8229a 76 arrToVar(length_st_joint_names, (inbuffer + offset));
Gary Servin 0:04ac6be8229a 77 offset += 4;
Gary Servin 0:04ac6be8229a 78 for(unsigned int k= offset; k< offset+length_st_joint_names; ++k){
Gary Servin 0:04ac6be8229a 79 inbuffer[k-1]=inbuffer[k];
Gary Servin 0:04ac6be8229a 80 }
Gary Servin 0:04ac6be8229a 81 inbuffer[offset+length_st_joint_names-1]=0;
Gary Servin 0:04ac6be8229a 82 this->st_joint_names = (char *)(inbuffer + offset-1);
Gary Servin 0:04ac6be8229a 83 offset += length_st_joint_names;
Gary Servin 0:04ac6be8229a 84 memcpy( &(this->joint_names[i]), &(this->st_joint_names), sizeof(char*));
Gary Servin 0:04ac6be8229a 85 }
Gary Servin 0:04ac6be8229a 86 uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 87 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 88 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 89 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 90 offset += sizeof(this->points_length);
Gary Servin 0:04ac6be8229a 91 if(points_lengthT > points_length)
Gary Servin 0:04ac6be8229a 92 this->points = (trajectory_msgs::MultiDOFJointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
Gary Servin 0:04ac6be8229a 93 points_length = points_lengthT;
Gary Servin 0:04ac6be8229a 94 for( uint32_t i = 0; i < points_length; i++){
Gary Servin 0:04ac6be8229a 95 offset += this->st_points.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 96 memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::MultiDOFJointTrajectoryPoint));
Gary Servin 0:04ac6be8229a 97 }
Gary Servin 0:04ac6be8229a 98 return offset;
Gary Servin 0:04ac6be8229a 99 }
Gary Servin 0:04ac6be8229a 100
Gary Servin 0:04ac6be8229a 101 const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectory"; };
Gary Servin 0:04ac6be8229a 102 const char * getMD5(){ return "ef145a45a5f47b77b7f5cdde4b16c942"; };
Gary Servin 0:04ac6be8229a 103
Gary Servin 0:04ac6be8229a 104 };
Gary Servin 0:04ac6be8229a 105
Gary Servin 0:04ac6be8229a 106 }
Gary Servin 0:04ac6be8229a 107 #endif