Skip to content

Commit

Permalink
Putting niut message in a specific file
Browse files Browse the repository at this point in the history
  • Loading branch information
Greg8978 committed Apr 21, 2015
1 parent 6aaa235 commit 50dec6a
Show file tree
Hide file tree
Showing 14 changed files with 106 additions and 32 deletions.
45 changes: 45 additions & 0 deletions niut_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
cmake_minimum_required(VERSION 2.8.3)
project(niut_msgs)

find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)

################################################
## Declare ROS messages, services and actions ##
################################################

# Generate messages in the 'msg' folder
add_message_files(
FILES
niut_GEN_POINT_3D.msg
niut_HUMAN_LIST.msg
niut_JOINT.msg
niut_JOINT_STR.msg
niut_SKELETON_STR.msg
niut_TIME_STR.msg
niut_TRACK_STATE.msg
niut_USER_STR.msg
)

# Generate services in the 'srv' folder
#add_service_files(
# FILES
# GetPersonTrajectories.srv
#)

## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)

###################################
## catkin specific configuration ##
###################################
catkin_package(
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
)
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
25 changes: 25 additions & 0 deletions niut_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<package>

<name>niut_msgs</name>
<version>0.0.0</version>
<description>Messages used for Person Detection and Tracking</description>

<maintainer email="[email protected]">Grégoire Milliez</maintainer>

<license>TODO</license>

<author email="[email protected]">Gregoire Milliez</author>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rospy</build_depend>

<run_depend>message_runtime</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>rospy</run_depend>

</package>
13 changes: 8 additions & 5 deletions pdg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
message_generation
spencer_tracking_msgs
niut_msgs
tf
)

Expand Down Expand Up @@ -51,10 +53,10 @@ find_package(catkin REQUIRED COMPONENTS
# Message1.msg
# Message2.msg
# )
add_message_files(FILES Agent.msg HumanList.msg niut_HUMAN_LIST.msg niut_TIME_STR.msg Object.msg
Entity.msg Human.msg niut_JOINT.msg niut_TRACK_STATE.msg RobotList.msg
FactList.msg Joint.msg niut_JOINT_STR.msg niut_USER_STR.msg Robot.msg
Fact.msg niut_GEN_POINT_3D.msg niut_SKELETON_STR.msg ObjectList.msg)
add_message_files(FILES Agent.msg HumanList.msg
Entity.msg Human.msg RobotList.msg
FactList.msg Joint.msg Robot.msg
Fact.msg ObjectList.msg Object.msg)

## Generate services in the 'srv' folder
# add_service_files(
Expand All @@ -75,6 +77,7 @@ Fact.msg niut_GEN_POINT_3D.msg niut_SKELETON_STR.msg ObjectList.msg)
DEPENDENCIES
std_msgs
spencer_tracking_msgs
niut_msgs
)
###################################
## catkin specific configuration ##
Expand All @@ -88,7 +91,7 @@ Fact.msg niut_GEN_POINT_3D.msg niut_SKELETON_STR.msg ObjectList.msg)
catkin_package(
INCLUDE_DIRS include
# LIBRARIES pdg
CATKIN_DEPENDS roscpp rospy std_msgs spencer_tracking_msgs message_generation message_runtime tf
CATKIN_DEPENDS roscpp rospy std_msgs spencer_tracking_msgs niut_msgs message_generation message_runtime tf
# DEPENDS system_lib
)

Expand Down
31 changes: 15 additions & 16 deletions pdg/include/pdg/NiutHumanReader.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,25 +13,24 @@
#define NIUTHUMANREADER_H

#include <ros/ros.h>
#include "pdg/niut_HUMAN_LIST.h"
#include "niut_msgs/niut_HUMAN_LIST.h"
#include "toaster-lib/Human.h"
#include "HumanReader.h"

class NiutHumanReader : public HumanReader{

public:
NiutHumanReader(ros::NodeHandle& node, double * kinectPos, bool fullHuman);

private:
static const unsigned short NB_MAX_NIUT = 16;
double* kinectPos_;
ros::Subscriber sub_;

//Functions
void humanJointCallBack(const pdg::niut_HUMAN_LIST::ConstPtr& msg);
void projectJoint(Joint& joint, double* kinectPos);
void updateJoint(int i, int j, Joint& curJoint, int toasterId, std::vector<int>& trackedJoints,
const pdg::niut_HUMAN_LIST::ConstPtr& msg);
class NiutHumanReader : public HumanReader {
public:
NiutHumanReader(ros::NodeHandle& node, double * kinectPos, bool fullHuman);

private:
static const unsigned short NB_MAX_NIUT = 16;
double* kinectPos_;
ros::Subscriber sub_;

//Functions
void humanJointCallBack(const niut_msgs::niut_HUMAN_LIST::ConstPtr& msg);
void projectJoint(Joint& joint, double* kinectPos);
void updateJoint(int i, int j, Joint& curJoint, int toasterId, std::vector<int>& trackedJoints,
const niut_msgs::niut_HUMAN_LIST::ConstPtr& msg);

};

Expand Down
20 changes: 11 additions & 9 deletions pdg/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,18 +39,20 @@
<!-- <run_depend>message_runtime</run_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>spencer_tracking_msgs</build_depend>
<buildtool_depend> catkin </buildtool_depend>
<build_depend> roscpp </build_depend>
<build_depend> rospy </build_depend>
<build_depend> std_msgs </build_depend>
<build_depend> spencer_tracking_msgs </build_depend>
<build_depend> niut_msgs </build_depend>
<build_depend> message_generation </build_depend>
<build_depend> tf </build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>spencer_tracking_msgs</run_depend>
<run_depend> roscpp </run_depend>
<run_depend> rospy </run_depend>
<run_depend> std_msgs </run_depend>
<run_depend> spencer_tracking_msgs </run_depend>
<run_depend> message_generation </run_depend>
<run_depend> niut_msgs </run_depend>
<run_depend> message_runtime </run_depend>
<run_depend> tf </run_depend>

Expand Down
4 changes: 2 additions & 2 deletions pdg/src/NiutHumanReader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ NiutHumanReader::NiutHumanReader(ros::NodeHandle& node, double * kinectPos,
sub_ = node_.subscribe("/niut/Human", 1, &NiutHumanReader::humanJointCallBack, this);
}

void NiutHumanReader::humanJointCallBack(const pdg::niut_HUMAN_LIST::ConstPtr& msg) {
void NiutHumanReader::humanJointCallBack(const niut_msgs::niut_HUMAN_LIST::ConstPtr& msg) {
Joint curJoint(10000, 100);
std::vector<int> trackedJoints;
trackedJoints.push_back(0);
Expand Down Expand Up @@ -75,7 +75,7 @@ void NiutHumanReader::humanJointCallBack(const pdg::niut_HUMAN_LIST::ConstPtr& m
}
}

void NiutHumanReader::updateJoint(int i, int j, Joint& curJoint, int toasterId, std::vector<int>& trackedJoints, const pdg::niut_HUMAN_LIST::ConstPtr& msg) {
void NiutHumanReader::updateJoint(int i, int j, Joint& curJoint, int toasterId, std::vector<int>& trackedJoints, const niut_msgs::niut_HUMAN_LIST::ConstPtr& msg) {

std::map<int, std::string> niutToString;
niutToString[0] = "HEAD";
Expand Down

0 comments on commit 50dec6a

Please sign in to comment.