Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 13 additions & 13 deletions cpp_common/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,19 +1,16 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(cpp_common)

find_package(ament_cmake REQUIRED)

set(Boost_USE_STATIC_LIBS ON)
find_package(Boost REQUIRED COMPONENTS system thread)
find_package(console_bridge REQUIRED)
find_package(catkin REQUIRED)
catkin_package(
DEPENDS Boost console_bridge
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME})

include(CheckIncludeFile)
include(CheckFunctionExists)
include(CheckCXXSourceCompiles)

include_directories(include ${Boost_INCLUDE_DIRS} ${console_bridge_INCLUDE_DIRS})
include_directories(include ${Boost_INCLUDE_DIRS})

# execinfo.h is needed for backtrace on glibc systems
CHECK_INCLUDE_FILE(execinfo.h HAVE_EXECINFO_H)
Expand All @@ -32,13 +29,16 @@ if(HAVE_GLIBC_BACKTRACE)
endif(HAVE_GLIBC_BACKTRACE)

add_library(${PROJECT_NAME} src/debug.cpp src/header.cpp)
target_link_libraries(${PROJECT_NAME} ${Boost_LIBRARIES} ${console_bridge_LIBRARIES})
target_link_libraries(${PROJECT_NAME})

ament_export_include_directories(include)
ament_package()

install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

install(DIRECTORY include/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
DESTINATION include
FILES_MATCHING PATTERN "*.h")
14 changes: 6 additions & 8 deletions cpp_common/package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<package>
<?xml version="1.0"?>
<package format="2">
<name>cpp_common</name>
<version>0.6.7</version>
<description>
Expand All @@ -15,11 +16,8 @@
<url>http://www.ros.org/wiki/cpp_common</url>
<author>John Faust</author>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>boost</build_depend>
<build_depend>libconsole-bridge-dev</build_depend>

<run_depend>boost</run_depend>
<run_depend>libconsole-bridge-dev</run_depend>
<buildtool_depend>ament_cmake</buildtool_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
14 changes: 7 additions & 7 deletions cpp_common/src/header.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
* * Neither the name of 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.
*
*90
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

typo?

Copy link
Copy Markdown
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

definitely :)

* 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
Expand All @@ -34,8 +34,6 @@

#include "ros/header.h"

#include "console_bridge/console.h"

#include <sstream>

#include <cstring>
Expand All @@ -46,11 +44,13 @@
#define SROS_DESERIALIZE_PRIMITIVE(ptr, data) { memcpy(&data, ptr, sizeof(data)); ptr += sizeof(data); }
#define SROS_DESERIALIZE_BUFFER(ptr, data, data_size) { if (data_size > 0) { memcpy(data, ptr, data_size); ptr += data_size; } }

// Remove this when no longer supporting platforms with libconsole-bridge-dev < 0.3.0,
// in particular Debian Jessie: https://packages.debian.org/jessie/libconsole-bridge-dev
#ifndef logError
#define logError(...)
#endif

// TODO: enable console bridge
#ifndef CONSOLE_BRIDGE_logError
# define CONSOLE_BRIDGE_logError(fmt, ...) \
console_bridge::log(__FILE__, __LINE__, console_bridge::CONSOLE_BRIDGE_LOG_ERROR, fmt, ##__VA_ARGS__)
#define CONSOLE_BRIDGE_logError logError
#endif

using namespace std;
Expand Down
Empty file added roscpp_core/AMENT_IGNORE
Empty file.
Empty file.
14 changes: 8 additions & 6 deletions roscpp_traits/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(roscpp_traits)
find_package(catkin REQUIRED)
catkin_package(
INCLUDE_DIRS include
CATKIN_DEPENDS cpp_common rostime)
find_package(ament_cmake REQUIRED)
find_package(cpp_common REQUIRED)
find_package(rostime REQUIRED)

ament_export_include_directories(include)
ament_package()

install(DIRECTORY include/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
DESTINATION include
FILES_MATCHING PATTERN "*.h")
69 changes: 29 additions & 40 deletions roscpp_traits/include/ros/message_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,47 +33,42 @@
#include <ros/datatypes.h>
#include <ros/message_traits.h>

#include <boost/type_traits/is_void.hpp>
#include <boost/type_traits/is_base_of.hpp>
#include <boost/type_traits/is_const.hpp>
#include <boost/type_traits/add_const.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/utility/enable_if.hpp>
#include <boost/function.hpp>
#include <boost/make_shared.hpp>
#include <type_traits>

namespace ros
{

template<typename M>
struct DefaultMessageCreator
{
boost::shared_ptr<M> operator()()
std::shared_ptr<M> operator()()
{
return boost::make_shared<M>();
return std::make_shared<M>();
}
};

template<typename M>
ROS_DEPRECATED inline boost::shared_ptr<M> defaultMessageCreateFunction()
ROS_DEPRECATED inline std::shared_ptr<M> defaultMessageCreateFunction()
{
return DefaultMessageCreator<M>()();
}

/**
* \brief Event type for subscriptions, const ros::MessageEvent<M const>& can be used in your callback instead of const boost::shared_ptr<M const>&
* \brief Event type for subscriptions, const ros::MessageEvent<M const>& can be used in your callback instead of const std::shared_ptr<M const>&
*
* Useful if you need to retrieve meta-data about the message, such as the full connection header, or the publisher's node name
*/
template<typename M>
class MessageEvent
{
public:
typedef typename boost::add_const<M>::type ConstMessage;
typedef typename boost::remove_const<M>::type Message;
typedef boost::shared_ptr<Message> MessagePtr;
typedef boost::shared_ptr<ConstMessage> ConstMessagePtr;
typedef boost::function<MessagePtr()> CreateFunction;
typedef typename std::add_const<M>::type ConstMessage;
typedef typename std::remove_const<M>::type Message;
typedef std::shared_ptr<Message> MessagePtr;
typedef std::shared_ptr<ConstMessage> ConstMessagePtr;
typedef std::function<MessagePtr()> CreateFunction;

typedef std::shared_ptr<M const> StdConstMessagePtr;

MessageEvent()
: nonconst_need_copy_(true)
Expand Down Expand Up @@ -103,33 +98,33 @@ class MessageEvent

MessageEvent(const MessageEvent<void const>& rhs, const CreateFunction& create)
{
init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
init(std::const_pointer_cast<Message>(std::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), create);
}

/**
* \todo Make this explicit in ROS 2.0. Keep as auto-converting for now to maintain backwards compatibility in some places (message_filters)
*/
MessageEvent(const ConstMessagePtr& message)
{
init(message, boost::shared_ptr<M_string>(), ros::Time::now(), true, ros::DefaultMessageCreator<Message>());
init(message, std::shared_ptr<M_string>(), ros::Time::now(), true, ros::DefaultMessageCreator<Message>());
}

MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
MessageEvent(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time)
{
init(message, connection_header, receipt_time, true, ros::DefaultMessageCreator<Message>());
}

MessageEvent(const ConstMessagePtr& message, ros::Time receipt_time)
{
init(message, boost::shared_ptr<M_string>(), receipt_time, true, ros::DefaultMessageCreator<Message>());
init(message, std::shared_ptr<M_string>(), receipt_time, true, ros::DefaultMessageCreator<Message>());
}

MessageEvent(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
MessageEvent(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
{
init(message, connection_header, receipt_time, nonconst_need_copy, create);
}

void init(const ConstMessagePtr& message, const boost::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
void init(const ConstMessagePtr& message, const std::shared_ptr<M_string>& connection_header, ros::Time receipt_time, bool nonconst_need_copy, const CreateFunction& create)
{
message_ = message;
connection_header_ = connection_header;
Expand All @@ -140,13 +135,13 @@ class MessageEvent

void operator=(const MessageEvent<Message>& rhs)
{
init(boost::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
init(std::static_pointer_cast<Message>(rhs.getMessage()), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
message_copy_.reset();
}

void operator=(const MessageEvent<ConstMessage>& rhs)
{
init(boost::const_pointer_cast<Message>(boost::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
init(std::const_pointer_cast<Message>(std::static_pointer_cast<ConstMessage>(rhs.getMessage())), rhs.getConnectionHeaderPtr(), rhs.getReceiptTime(), rhs.nonConstWillCopy(), rhs.getMessageFactory());
message_copy_.reset();
}

Expand All @@ -155,20 +150,20 @@ class MessageEvent
* and this event requires it, returns a copy. Note that it caches this copy for later use, so it will
* only every make the copy once
*/
boost::shared_ptr<M> getMessage() const
std::shared_ptr<M> getMessage() const
{
return copyMessageIfNecessary<M>();
}

/**
* \brief Retrieve a const version of the message
*/
const boost::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
const std::shared_ptr<ConstMessage>& getConstMessage() const { return message_; }
/**
* \brief Retrieve the connection header
*/
M_string& getConnectionHeader() const { return *connection_header_; }
const boost::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }
const std::shared_ptr<M_string>& getConnectionHeaderPtr() const { return connection_header_; }

/**
* \brief Returns the name of the node which published this message
Expand All @@ -181,7 +176,7 @@ class MessageEvent
ros::Time getReceiptTime() const { return receipt_time_; }

bool nonConstWillCopy() const { return nonconst_need_copy_; }
bool getMessageWillCopy() const { return !boost::is_const<M>::value && nonconst_need_copy_; }
bool getMessageWillCopy() const { return !std::is_const<M>::value && nonconst_need_copy_; }

bool operator<(const MessageEvent<M>& rhs)
{
Expand Down Expand Up @@ -211,12 +206,12 @@ class MessageEvent
const CreateFunction& getMessageFactory() const { return create_; }

private:
template<typename M2>
typename boost::disable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
template<typename M>
std::shared_ptr<M> copyMessageIfNecessary() const
{
if (boost::is_const<M>::value || !nonconst_need_copy_)
if (std::is_const<M>::value || !nonconst_need_copy_)
{
return boost::const_pointer_cast<Message>(message_);
return std::const_pointer_cast<Message>(message_);
}

if (message_copy_)
Expand All @@ -231,16 +226,10 @@ class MessageEvent
return message_copy_;
}

template<typename M2>
typename boost::enable_if<boost::is_void<M2>, boost::shared_ptr<M> >::type copyMessageIfNecessary() const
{
return boost::const_pointer_cast<Message>(message_);
}

ConstMessagePtr message_;
// Kind of ugly to make this mutable, but it means we can pass a const MessageEvent to a callback and not worry about other things being modified
mutable MessagePtr message_copy_;
boost::shared_ptr<M_string> connection_header_;
std::shared_ptr<M_string> connection_header_;
ros::Time receipt_time_;
bool nonconst_need_copy_;
CreateFunction create_;
Expand Down
15 changes: 10 additions & 5 deletions roscpp_traits/package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<package>
<?xml version="1.0"?>
<package format="2">
<name>roscpp_traits</name>
<version>0.6.7</version>
<description>
Expand All @@ -13,8 +14,12 @@
<url type="website">http://ros.org/wiki/roscpp_traits</url>
<author>Josh Faust</author>

<buildtool_depend>catkin</buildtool_depend>

<run_depend>cpp_common</run_depend>
<run_depend>rostime</run_depend>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>cpp_common</build_depend>
<build_depend>rostime</build_depend>
<exec_depend>cpp_common</exec_depend>
<exec_depend>rostime</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
48 changes: 19 additions & 29 deletions rostime/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,44 +1,34 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(rostime)

find_package(catkin REQUIRED COMPONENTS cpp_common)
find_package(Boost REQUIRED COMPONENTS date_time system thread)
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS cpp_common
DEPENDS Boost
)
find_package(ament_cmake REQUIRED)
find_package(cpp_common REQUIRED)

set(Boost_USE_STATIC_LIBS ON)
find_package(Boost REQUIRED)

include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
include_directories(include
${cpp_common_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)

add_library(rostime
src/duration.cpp
src/rate.cpp
src/time.cpp)

target_link_libraries(rostime ${Boost_LIBRARIES})
if(NOT APPLE)
target_link_libraries(rostime ${RT_LIBRARY})
endif()
target_link_libraries(rostime)

ament_export_include_directories(include)
ament_export_libraries(rostime)
ament_package()

install(TARGETS rostime
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

install(DIRECTORY include/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
DESTINATION include
FILES_MATCHING PATTERN "*.h")

if(CATKIN_ENABLE_TESTING)
catkin_add_gtest(${PROJECT_NAME}-test_duration test/duration.cpp)
if(TARGET ${PROJECT_NAME}-test_duration)
target_link_libraries(${PROJECT_NAME}-test_duration ${catkin_LIBRARIES} rostime)
endif()
catkin_add_gtest(${PROJECT_NAME}-test_time test/time.cpp)
if(TARGET ${PROJECT_NAME}-test_time)
set_property(TARGET ${PROJECT_NAME}-test_time APPEND_STRING PROPERTY COMPILE_FLAGS "-std=c++11")
target_link_libraries(${PROJECT_NAME}-test_time ${catkin_LIBRARIES} rostime)
endif()
endif()
Loading