Skip to content

Commit

Permalink
Move the header files to .hpp extension (#206)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Dec 7, 2024
1 parent d3f9eef commit d49502c
Show file tree
Hide file tree
Showing 16 changed files with 815 additions and 715 deletions.
83 changes: 13 additions & 70 deletions include/realtime_tools/realtime_box.h
Original file line number Diff line number Diff line change
@@ -1,77 +1,20 @@
// Copyright (c) 2009, Willow Garage, Inc.
// Copyright 2024 ros2_control Development Team
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// http://www.apache.org/licenses/LICENSE-2.0
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage, Inc. nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

// Author: Stuart Glaser

#ifndef REALTIME_TOOLS__REALTIME_BOX_H__
#define REALTIME_TOOLS__REALTIME_BOX_H__

#include <mutex>
#include <string>

namespace realtime_tools
{
/*!
Strongly suggested that you use an std::shared_ptr in this box to
guarantee realtime safety.
*/
template <class T>
class RealtimeBox
{
public:
explicit RealtimeBox(const T & initial = T()) : thing_(initial) {}

void set(const T & value)
{
std::lock_guard<std::mutex> guard(thing_lock_RT_);
thing_ = value;
}

void get(T & ref)
{
std::lock_guard<std::mutex> guard(thing_lock_RT_);
ref = thing_;
}

private:
// The thing that's in the box.
T thing_;
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

// Protects access to the thing in the box. This mutex is
// guaranteed to be locked for no longer than the duration of the
// copy, so as long as the copy is realtime safe and the OS has
// priority inheritance for mutexes, this lock can be safely locked
// from within realtime.
std::mutex thing_lock_RT_;
};
#ifndef REALTIME_TOOLS__REALTIME_BOX_H_
#define REALTIME_TOOLS__REALTIME_BOX_H_

} // namespace realtime_tools
#include "realtime_tools/realtime_box.hpp"

#endif // REALTIME_TOOLS__REALTIME_BOX_H_
77 changes: 77 additions & 0 deletions include/realtime_tools/realtime_box.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
// Copyright (c) 2009, Willow Garage, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage, Inc. nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

// Author: Stuart Glaser

#ifndef REALTIME_TOOLS__REALTIME_BOX_HPP_
#define REALTIME_TOOLS__REALTIME_BOX_HPP_

#include <mutex>
#include <string>

namespace realtime_tools
{
/*!
Strongly suggested that you use an std::shared_ptr in this box to
guarantee realtime safety.
*/
template <class T>
class RealtimeBox
{
public:
explicit RealtimeBox(const T & initial = T()) : thing_(initial) {}

void set(const T & value)
{
std::lock_guard<std::mutex> guard(thing_lock_RT_);
thing_ = value;
}

void get(T & ref)
{
std::lock_guard<std::mutex> guard(thing_lock_RT_);
ref = thing_;
}

private:
// The thing that's in the box.
T thing_;

// Protects access to the thing in the box. This mutex is
// guaranteed to be locked for no longer than the duration of the
// copy, so as long as the copy is realtime safe and the OS has
// priority inheritance for mutexes, this lock can be safely locked
// from within realtime.
std::mutex thing_lock_RT_;
};

} // namespace realtime_tools

#endif // REALTIME_TOOLS__REALTIME_BOX_HPP_
181 changes: 11 additions & 170 deletions include/realtime_tools/realtime_buffer.h
Original file line number Diff line number Diff line change
@@ -1,179 +1,20 @@
// Copyright (c) 2013, hiDOF, Inc.
// Copyright 2024 ros2_control Development Team
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// http://www.apache.org/licenses/LICENSE-2.0
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the hiDOF, Inc. nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

/*
* Publishing ROS messages is difficult, as the publish function is
* not realtime safe. This class provides the proper locking so that
* you can call publish in realtime and a separate (non-realtime)
* thread will ensure that the message gets published over ROS.
*
* Author: Wim Meeussen
*/
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef REALTIME_TOOLS__REALTIME_BUFFER_H_
#define REALTIME_TOOLS__REALTIME_BUFFER_H_

#include <chrono>
#include <mutex>
#include <thread>

namespace realtime_tools
{
template <class T>
class RealtimeBuffer
{
public:
RealtimeBuffer() : new_data_available_(false)
{
// allocate memory
non_realtime_data_ = new T();
realtime_data_ = new T();
}

/**
* @brief Constructor for objects that don't have
* a default constructor
* @param data The object to use as default value
*/
explicit RealtimeBuffer(const T & data) : new_data_available_(false)
{
// allocate memory
non_realtime_data_ = new T(data);
realtime_data_ = new T(data);
}

~RealtimeBuffer()
{
if (non_realtime_data_) {
delete non_realtime_data_;
}
if (realtime_data_) {
delete realtime_data_;
}
}

RealtimeBuffer(const RealtimeBuffer & source)
{
// allocate memory
non_realtime_data_ = new T();
realtime_data_ = new T();

// Copy the data from old RTB to new RTB
writeFromNonRT(*source.readFromNonRT());
}

/*!
* @brief Custom assignment operator
*/
RealtimeBuffer & operator=(const RealtimeBuffer & source)
{
if (this == &source) {
return *this;
}

// Copy the data from old RTB to new RTB
writeFromNonRT(*source.readFromNonRT());

return *this;
}

T * readFromRT()
{
// Check if the data is currently being written to (is locked)
std::unique_lock<std::mutex> guard(mutex_, std::try_to_lock);
if (guard.owns_lock()) {
// swap pointers
if (new_data_available_) {
T * tmp = realtime_data_;
realtime_data_ = non_realtime_data_;
non_realtime_data_ = tmp;
new_data_available_ = false;
}
}
return realtime_data_;
}

T * readFromNonRT() const
{
std::lock_guard<std::mutex> guard(mutex_);

if (new_data_available_) {
return non_realtime_data_;
} else {
return realtime_data_;
}
}

void writeFromNonRT(const T & data)
{
#ifdef NON_POLLING
std::lock_guard<std::mutex> guard(mutex_);
#else
std::unique_lock<std::mutex> guard(mutex_, std::defer_lock);
while (!guard.try_lock()) {
std::this_thread::sleep_for(std::chrono::microseconds(500));
}
#endif

// copy data into non-realtime buffer
*non_realtime_data_ = data;
new_data_available_ = true;
}

void initRT(const T & data)
{
*non_realtime_data_ = data;
*realtime_data_ = data;
}

void reset()
{
// delete the old memory
if (non_realtime_data_) {
delete non_realtime_data_;
}
if (realtime_data_) {
delete realtime_data_;
}

// allocate memory
non_realtime_data_ = new T();
realtime_data_ = new T();
}

private:
T * realtime_data_;
T * non_realtime_data_;
bool new_data_available_;

// Set as mutable so that readFromNonRT() can be performed on a const buffer
mutable std::mutex mutex_;
}; // class
#include "realtime_tools/realtime_buffer.hpp"

} // namespace realtime_tools
#endif // REALTIME_TOOLS__REALTIME_BUFFER_H_
Loading

0 comments on commit d49502c

Please sign in to comment.