diff --git a/launch/k2_client.launch b/launch/k2_client.launch index 4b23c9d..802817f 100644 --- a/launch/k2_client.launch +++ b/launch/k2_client.launch @@ -1,5 +1,6 @@ - + + @@ -12,3 +13,5 @@ + + diff --git a/package.xml b/package.xml index 7e4d761..b3efafe 100644 --- a/package.xml +++ b/package.xml @@ -22,6 +22,7 @@ cv_bridge image_transport camera_info_manager + jsoncpp diff --git a/src/startBody.cpp b/src/startBody.cpp index 1be4a64..43efc2b 100644 --- a/src/startBody.cpp +++ b/src/startBody.cpp @@ -30,9 +30,9 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH #include std::string topicName = "bodyArray"; -size_t streamSize = 56008; -size_t readSkipSize = 56000; -size_t stringSize = 28000; +size_t streamSize = 80008; +size_t readSkipSize = 80000; +size_t stringSize = 40000; int main(int argC,char **argV) { @@ -44,29 +44,36 @@ int main(int argC,char **argV) iconv_t charConverter = iconv_open("UTF-8","UTF-16"); ros::Publisher bodyPub = n.advertise(topicName,1); char jsonCharArray[readSkipSize]; - + while(ros::ok()) { - mySocket.readData(); + mySocket.readData(); char *jsonCharArrayPtr; char *socketCharArrayPtr; + size_t readSkipSizeC = readSkipSize; + size_t stringSizeloC= stringSize; jsonCharArrayPtr = jsonCharArray; - socketCharArrayPtr = mySocket.mBuffer; - iconv(charConverter,&socketCharArrayPtr,&readSkipSize,&jsonCharArrayPtr,&stringSize); + socketCharArrayPtr = mySocket.mBuffer; + iconv(charConverter,&socketCharArrayPtr,&readSkipSizeC,&jsonCharArrayPtr,&stringSizeloC); double utcTime; - memcpy(&utcTime,&mySocket.mBuffer[readSkipSize],sizeof(double)); + memcpy(&utcTime,&mySocket.mBuffer[readSkipSizeC],sizeof(double)); std::string jsonString(jsonCharArray); Json::Value jsonObject; Json::Reader jsonReader; bool parsingSuccessful = jsonReader.parse(jsonString,jsonObject,false); + if(!parsingSuccessful) { ROS_ERROR("Failure to parse"); - continue; } + + if (jsonObject.size() != 6) + continue; + k2_client::BodyArray bodyArray; try { + //ROS_ERROR("Parsing successulff"); for(int i=0;i<6;i++) { k2_client::Body body; @@ -124,13 +131,13 @@ int main(int argC,char **argV) case 23: fieldName = "HandTipRight";break; case 24: fieldName = "ThumbRight";break; } - + JOAT.orientation.x = jsonObject[i]["JointOrientations"][fieldName]["Orientation"]["X"].asDouble(); JOAT.orientation.y = jsonObject[i]["JointOrientations"][fieldName]["Orientation"]["Y"].asDouble(); JOAT.orientation.z = jsonObject[i]["JointOrientations"][fieldName]["Orientation"]["Z"].asDouble(); JOAT.orientation.w = jsonObject[i]["JointOrientations"][fieldName]["Orientation"]["W"].asDouble(); JOAT.jointType = jsonObject[i]["JointOrientations"][fieldName]["JointType"].asInt(); - + JPAS.trackingState = jsonObject[i]["Joints"][fieldName]["TrackingState"].asBool(); JPAS.position.x = jsonObject[i]["Joints"][fieldName]["Position"]["X"].asDouble(); JPAS.position.y = jsonObject[i]["Joints"][fieldName]["Position"]["Y"].asDouble(); @@ -140,6 +147,7 @@ int main(int argC,char **argV) body.jointOrientations.push_back(JOAT); body.jointPositions.push_back(JPAS); } + //std::cout << ros::Time::now() <