Skip to content

Commit

Permalink
Use new factory method of libmotioncapture
Browse files Browse the repository at this point in the history
  • Loading branch information
whoenig committed Aug 6, 2021
1 parent 2f2dbfc commit 2d2deeb
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 101 deletions.
16 changes: 0 additions & 16 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -131,22 +131,6 @@ link_directories(
${LIBMOTIONCAPTURE_LINK_DIR}
)

if (ENABLE_VICON)
add_definitions(-DENABLE_VICON)
endif()
if (ENABLE_OPTITRACK)
add_definitions(-DENABLE_OPTITRACK)
endif()
if (ENABLE_PHASESPACE)
add_definitions(-DENABLE_PHASESPACE)
endif()
if (ENABLE_QUALISYS)
add_definitions(-DENABLE_QUALISYS)
endif()
if (ENABLE_VRPN)
add_definitions(-DENABLE_VRPN)
endif()

## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/motion_capture_tracking.cpp
Expand Down
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
[![ROS](https://github.com/whoenig/motion_capture_tracking/actions/workflows/ROS.yml/badge.svg?branch=main)](https://github.com/whoenig/motion_capture_tracking/actions/workflows/ROS.yml)
[![ROS](https://github.com/IMRCLab/motion_capture_tracking/actions/workflows/ROS.yml/badge.svg?branch=main)](https://github.com/IMRCLab/motion_capture_tracking/actions/workflows/ROS.yml)

# motion_capture_tracking

Expand All @@ -10,7 +10,7 @@ To build from source, clone the latest version from this repository into your ca

```
cd catkin_workspace/src
git clone --recurse-submodules https://github.com/whoenig/motion_capture_tracking
git clone --recurse-submodules https://github.com/IMRCLab/motion_capture_tracking
cd ../
catkin_make
```
```
9 changes: 2 additions & 7 deletions launch/node.launch
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,10 @@
<rosparam>
# Tracking
motion_capture_type: "qualisys" # one of vicon,optitrack,qualisys,vrpn
motion_capture_hostname: "localhost"
object_tracking_type: "libobjecttracker" # one of motionCapture,libobjecttracker
# vicon_host_name: "192.168.50.253"
# optitrack_host_name: "optitrack"
qualisys_host_name: "192.168.5.21"
qualisys_base_port: 22222
# vrpn_host_name: "vicon"

save_point_clouds_path: "" # leave empty to not write point cloud to file

save_point_clouds_path: "" # leave empty to not write point cloud to file

numMarkerConfigurations: 1
markerConfigurations:
Expand Down
78 changes: 4 additions & 74 deletions src/motion_capture_tracking_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,7 @@
#include <sensor_msgs/PointCloud.h>

// Motion Capture
#ifdef ENABLE_VICON
#include <libmotioncapture/vicon.h>
#endif
#ifdef ENABLE_OPTITRACK
#include <libmotioncapture/optitrack.h>
#endif
#ifdef ENABLE_PHASESPACE
#include <libmotioncapture/phasespace.h>
#endif
#ifdef ENABLE_QUALISYS
#include <libmotioncapture/qualisys.h>
#endif
#ifdef ENABLE_VRPN
#include <libmotioncapture/vrpn.h>
#endif
#include <libmotioncapture/motioncapture.h>

// Object tracker
#include <libobjecttracker/object_tracker.h>
Expand All @@ -37,68 +23,12 @@ int main(int argc, char **argv)

ros::NodeHandle nl("~");

std::string motionCaptureType;
std::string motionCaptureType, motionCaptureHostname;
nl.param<std::string>("motion_capture_type", motionCaptureType, "vicon");
nl.param<std::string>("motion_capture_hostname", motionCaptureHostname, "localhost");

// Make a new client
libmotioncapture::MotionCapture* mocap = nullptr;
if (false)
{
}
#ifdef ENABLE_VICON
else if (motionCaptureType == "vicon")
{
std::string hostName;
nl.getParam("vicon_host_name", hostName);
mocap = new libmotioncapture::MotionCaptureVicon(hostName,
/*enableObjects*/ true,
/*enablePointcloud*/ true);
}
#endif
#ifdef ENABLE_OPTITRACK
else if (motionCaptureType == "optitrack")
{
std::string hostName;
nl.getParam("optitrack_host_name", hostName);
mocap = new libmotioncapture::MotionCaptureOptitrack(hostName);
}
#endif
#ifdef ENABLE_PHASESPACE
else if (motionCaptureType == "phasespace")
{
std::string ip;
int numMarkers;
nl.getParam("phasespace_ip", ip);
nl.getParam("phasespace_num_markers", numMarkers);
std::map<size_t, std::pair<int, int> > cfs;
cfs[231] = std::make_pair<int, int>(10, 11);
mocap = new libmotioncapture::MotionCapturePhasespace(ip, numMarkers, cfs);
}
#endif
#ifdef ENABLE_QUALISYS
else if (motionCaptureType == "qualisys")
{
std::string hostname;
int port;
nl.getParam("qualisys_host_name", hostname);
nl.getParam("qualisys_base_port", port);
mocap = new libmotioncapture::MotionCaptureQualisys(hostname, port,
/*enableObjects*/ true,
/*enablePointcloud*/ true);
}
#endif
#ifdef ENABLE_VRPN
else if (motionCaptureType == "vrpn")
{
std::string hostname;
int port;
nl.getParam("vrpn_host_name", hostname);
mocap = new libmotioncapture::MotionCaptureVrpn(hostname);
}
#endif
else {
throw std::runtime_error("Unknown motion capture type!");
}
libmotioncapture::MotionCapture *mocap = libmotioncapture::MotionCapture::connect(motionCaptureType, motionCaptureHostname);

// prepare point cloud publisher
ros::Publisher pubPointCloud = nl.advertise<sensor_msgs::PointCloud>("pointCloud", 1);
Expand Down

0 comments on commit 2d2deeb

Please sign in to comment.