Skip to content

Commit

Permalink
Catkinized pi_tracker package for Hydro
Browse files Browse the repository at this point in the history
  • Loading branch information
Patrick Goebel committed Jan 1, 2014
1 parent 2346cab commit 563e6e6
Show file tree
Hide file tree
Showing 12 changed files with 336 additions and 170 deletions.
60 changes: 32 additions & 28 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,34 +1,38 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
cmake_minimum_required(VERSION 2.8.3)
project(pi_tracker)

# Set the build type. Options are:
# Coverage : w/ debug symbols, w/o optimization, w/ code-coverage
# Debug : w/ debug symbols, w/o optimization
# Release : w/o debug symbols, w/ optimization
# RelWithDebInfo : w/ debug symbols, w/ optimization
# MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries
#set(ROS_BUILD_TYPE RelWithDebInfo)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
# tf
std_msgs
geometry_msgs
nav_msgs
message_generation)

rosbuild_init()
link_directories(
${catkin_LIBRARY_DIRS}
#${Boost_LIBRARY_DIRS}
)

#set the default path for built executables to the "bin" directory
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
#set the default path for built libraries to the "lib" directory
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
include_directories(${catkin_INCLUDE_DIRS})

#uncomment if you have defined messages
rosbuild_genmsg()
add_service_files(DIRECTORY srv
FILES
SetCommand.srv)

#uncomment if you have defined services
rosbuild_gensrv()
generate_messages(
DEPENDENCIES geometry_msgs std_msgs nav_msgs
)

catkin_package(
DEPENDS #
CATKIN DEPENDS message_runtime
rospy
roscpp
# tf
# nav_msgs
# std_msgs
# geometry_msgs
)

#common commands for building c++ executables and libraries
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
#target_link_libraries(${PROJECT_NAME} another_library)
#rosbuild_add_boost_directories()
#rosbuild_link_boost(${PROJECT_NAME} thread)
#rosbuild_add_executable(example examples/example.cpp)
#target_link_libraries(example ${PROJECT_NAME})
include_directories(/usr/include/openni /usr/include/nite /usr/include/ni)
rosbuild_add_executable(skeleton_tracker src/skeleton_tracker.cpp src/KinectController.cpp src/KinectDisplay.cpp)
target_link_libraries(skeleton_tracker glut OpenNI orocos-kdl tf)
1 change: 0 additions & 1 deletion Makefile

This file was deleted.

2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
Skeleton Tracker Teleop Package for the Pi Robot Project.

The Hydro version (branch hydro-devel) has been catkinized and now depends on skeleton\_markers for the skeleton\_tracker node.
4 changes: 2 additions & 2 deletions launch/skeleton.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,13 @@
<include file="$(find rgbd_launch)/launch/kinect_frames.launch" />

<group if="$(arg debug)">
<node launch-prefix="$(arg launch_prefix)" name="skeleton_tracker" pkg="pi_tracker" type="skeleton_tracker" output="screen" >
<node launch-prefix="$(arg launch_prefix)" name="skeleton_tracker" pkg="skeleton_markers" type="skeleton_tracker" output="screen" >
<param name="fixed_frame" value="$(arg fixed_frame)" />
<param name="load_filepath" value="$(find pi_tracker)/params/SamplesConfigNewOpenNI.xml" />
</node>
</group>
<group unless="$(arg debug)">
<node name="skeleton_tracker" pkg="pi_tracker" type="skeleton_tracker">
<node name="skeleton_tracker" pkg="skeleton_markers" type="skeleton_tracker">
<param name="fixed_frame" value="$(arg fixed_frame)" />
<param name="load_filepath" value="$(find pi_tracker)/params/SamplesConfigNewOpenNI.xml" />
</node>
Expand Down
7 changes: 0 additions & 7 deletions launch/track_joint.launch

This file was deleted.

23 changes: 0 additions & 23 deletions manifest.xml

This file was deleted.

106 changes: 0 additions & 106 deletions markers.rviz

This file was deleted.

2 changes: 1 addition & 1 deletion nodes/tracker_base_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
import rospy
from geometry_msgs.msg import Twist
import pi_tracker_lib as PTL
from pi_tracker.msg import Skeleton
from skeleton_markers.msg import Skeleton
from pi_tracker.srv import *
import PyKDL as KDL
from math import atan2, sqrt, copysign, pi
Expand Down
2 changes: 1 addition & 1 deletion nodes/tracker_command.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

import rospy
import pi_tracker_lib as PTL
from pi_tracker.msg import Skeleton
from skeleton_markers.msg import Skeleton
from pi_tracker.srv import *
import PyKDL as KDL
from math import copysign
Expand Down
2 changes: 1 addition & 1 deletion nodes/tracker_joint_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
import rospy
import pi_tracker_lib as PTL
from sensor_msgs.msg import JointState
from pi_tracker.msg import Skeleton
from skeleton_markers.msg import Skeleton
from pi_tracker.srv import *
import PyKDL as KDL
from math import acos, asin, pi
Expand Down
33 changes: 33 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<package>
<name>pi_tracker</name>
<version>0.4.0</version>
<description>
Skeleton Tracker Teleop Package for the Pi Robot Project
</description>

<maintainer email="[email protected]">Patrick Goebel</maintainer>
<license>BSD</license>
<url type="website">http://ros.org/wiki/pi_tracker</url>
<url type="https://github.com/pirobot/pi_tracker/issues"></url>
<author email="[email protected]">Patrick Goebel</author>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>geometry_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rospy</build_depend>
<build_depend>roscpp</build_depend>

<run_depend>skeleton_markers</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>rospy</run_depend>
<run_depend>roscpp</run_depend>

</package>
Loading

0 comments on commit 563e6e6

Please sign in to comment.