Skip to content

Commit

Permalink
move realtime tools in ros control, and create empty constructors for…
Browse files Browse the repository at this point in the history
… handles
  • Loading branch information
Wim Meeussen committed Dec 23, 2012
1 parent cef7857 commit 2a3c118
Show file tree
Hide file tree
Showing 13 changed files with 61 additions and 36 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ namespace hardware_interface
class JointHandle : public JointStateHandle
{
public:
JointHandle() {};
JointHandle(const JointStateHandle& js, double* cmd)
: JointStateHandle(js), cmd_(cmd)
{}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ namespace hardware_interface{
class JointStateHandle
{
public:
JointStateHandle() {};
JointStateHandle(const std::string& name, const double* pos, const double* vel, const double* eff)
: name_(name), pos_(pos), vel_(vel), eff_(eff)
{}
Expand Down
5 changes: 5 additions & 0 deletions realtime_tools/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
rosbuild_init()
#rosbuild_genmsg()
rosbuild_add_boost_directories()
1 change: 1 addition & 0 deletions realtime_tools/Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
include $(shell rospack find mk)/cmake.mk
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,15 @@

// Author: Stuart Glaser

#ifndef REALTIME_UTILS_REALTIME_BOX_H__
#define REALTIME_UTILS_REALTIME_BOX_H__
#ifndef REALTIME_BOX_H__
#define REALTIME_BOX_H__

#include <string>
#include <ros/node_handle.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>

namespace realtime_utils {
namespace realtime_tools {

/*!
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
*
* Author: Stuart Glaser
*/
#ifndef REALTIME_UTILS_REALTIME_PUBLISHER_H
#define REALTIME_UTILS_REALTIME_PUBLISHER_H
#ifndef REALTIME_PUBLISHER_H
#define REALTIME_PUBLISHER_H

#include <string>
#include <ros/node_handle.h>
Expand All @@ -45,7 +45,7 @@
#include <boost/thread/thread.hpp>
#include <boost/thread/condition.hpp>

namespace realtime_utils {
namespace realtime_tools {

template <class Msg>
class RealtimePublisher : boost::noncopyable
Expand Down
27 changes: 27 additions & 0 deletions realtime_tools/manifest.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<package>
<description brief="Realtime tools">
This package contains a set of tools that can be used from a hard
realtime thread, without breaking the realtime behavior. The
tools currently only provides the realtime publisher, which makes
it possible to publish messages to a ROS topic from a realtime
thread. We plan to add a basic implementation of a realtime
buffer, to make it possible to get data from a (non-realtime)
topic callback into tha realtime loop. Once the lockfree buffer is
created, the realtime publisher will start using it, which will
result in major API changes for the realtime publisher (removal of
all lock methods).
</description>
<author>Stuart Glaser &lt;sglaser@willowgarage.com&gt;</author>
<license>BSD</license>
<review status="doc reviewed"/>
<url>http://ros.org/wiki/realtime_tools</url>
<depend package="roscpp"/>
<depend package="rospy" />
<export>
<cpp cflags="-I${prefix}/include " />
</export>
<platform os="ubuntu" version="9.04"/>
<platform os="ubuntu" version="9.10"/>
<platform os="ubuntu" version="10.04"/>
</package>

File renamed without changes.
12 changes: 0 additions & 12 deletions realtime_utils/CMakeLists.txt

This file was deleted.

1 change: 0 additions & 1 deletion realtime_utils/Makefile

This file was deleted.

17 changes: 0 additions & 17 deletions realtime_utils/manifest.xml

This file was deleted.

20 changes: 20 additions & 0 deletions stack.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<stack>
<description brief="ROS Control">
The new ros controller manager
</description>
<author>Maintained by Wim Meeussen</author>
<license>BSD</license>
<review status="Doc reviewed" notes="2009-11-13"/>
<url>http://ros.org/wiki/ros_control</url>
<depend stack="pluginlib" /> <!-- pluginlib -->
<depend stack="ros_comm" /> <!-- std_msgs, std_srvs, rosparam, rospy, roscpp -->
<depend stack="ros" />

<depend stack="common_msgs" /> <!-- geometry_msgs, sensor_msgs, diagnostic_msgs -->
<depend stack="diagnostics" /> <!-- diagnostic_updater -->
<depend stack="geometry" /> <!-- angles -->
<depend stack="pr2_common" /> <!-- pr2_description -->
<depend stack="robot_model" /> <!-- urdf_interface, robot_state_publisher, urdf, kdl_parser -->


</stack>

0 comments on commit 2a3c118

Please sign in to comment.