Skip to content

Commit

Permalink
Merge pull request #23 from scpeters/unboost
Browse files Browse the repository at this point in the history
Use c++11 instead of boost, bump version to 1.0.0
  • Loading branch information
scpeters authored Jul 20, 2016
2 parents 76da8dc + 9d2b421 commit 5cb0b6b
Show file tree
Hide file tree
Showing 8 changed files with 106 additions and 35 deletions.
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@ project (urdfdom_headers)

include(GNUInstallDirs)

set (URDF_MAJOR_VERSION 0)
set (URDF_MINOR_VERSION 4)
set (URDF_PATCH_VERSION 2)
set (URDF_MAJOR_VERSION 1)
set (URDF_MINOR_VERSION 0)
set (URDF_PATCH_VERSION 0)

set (URDF_VERSION ${URDF_MAJOR_VERSION}.${URDF_MINOR_VERSION}.${URDF_PATCH_VERSION})

Expand Down
15 changes: 9 additions & 6 deletions urdf_model/include/urdf_model/color.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,12 @@
#ifndef URDF_INTERFACE_COLOR_H
#define URDF_INTERFACE_COLOR_H

#include <stdexcept>
#include <string>
#include <vector>
#include <math.h>
#include <boost/algorithm/string.hpp>
#include <boost/lexical_cast.hpp>

#include <urdf_model/utils.h>

namespace urdf
{
Expand All @@ -65,17 +66,19 @@ class Color
this->clear();
std::vector<std::string> pieces;
std::vector<float> rgba;
boost::split( pieces, vector_str, boost::is_any_of(" "));
urdf::split_string( pieces, vector_str, " ");
for (unsigned int i = 0; i < pieces.size(); ++i)
{
if (!pieces[i].empty())
{
try
{
rgba.push_back(boost::lexical_cast<float>(pieces[i].c_str()));
rgba.push_back(std::stof(pieces[i]));
}
catch (boost::bad_lexical_cast &/*e*/)
{
catch (std::invalid_argument &/*e*/) {
return false;
}
catch (std::out_of_range &/*e*/) {
return false;
}
}
Expand Down
17 changes: 10 additions & 7 deletions urdf_model/include/urdf_model/pose.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,13 @@
#endif

#include <cmath>
#include <string>
#include <sstream>
#include <stdexcept>
#include <string>
#include <vector>

#include <boost/algorithm/string.hpp>
#include <boost/lexical_cast.hpp>
#include <urdf_exception/exception.h>
#include <urdf_model/utils.h>

namespace urdf{

Expand All @@ -71,20 +71,23 @@ class Vector3
this->clear();
std::vector<std::string> pieces;
std::vector<double> xyz;
boost::split( pieces, vector_str, boost::is_any_of(" "));
urdf::split_string( pieces, vector_str, " ");
for (unsigned int i = 0; i < pieces.size(); ++i){
if (pieces[i] != ""){
try {
xyz.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
xyz.push_back(std::stod(pieces[i]));
}
catch (boost::bad_lexical_cast &/*e*/) {
catch (std::invalid_argument &/*e*/) {
throw ParseError("Unable to parse component [" + pieces[i] + "] to a double (while parsing a vector value)");
}
catch (std::out_of_range &/*e*/) {
throw ParseError("Unable to parse component [" + pieces[i] + "] to a double, out of range (while parsing a vector value)");
}
}
}

if (xyz.size() != 3)
throw ParseError("Parser found " + boost::lexical_cast<std::string>(xyz.size()) + " elements but 3 expected while parsing vector [" + vector_str + "]");
throw ParseError("Parser found " + std::to_string(xyz.size()) + " elements but 3 expected while parsing vector [" + vector_str + "]");

this->x = xyz[0];
this->y = xyz[1];
Expand Down
24 changes: 11 additions & 13 deletions urdf_model/include/urdf_model/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,20 +37,18 @@
#ifndef URDF_MODEL_TYPES_H
#define URDF_MODEL_TYPES_H

#include <boost/pointer_cast.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <memory>

#define URDF_TYPEDEF_CLASS_POINTER(Class) \
class Class; \
typedef boost::shared_ptr<Class> Class##SharedPtr; \
typedef boost::shared_ptr<const Class> Class##ConstSharedPtr; \
typedef boost::weak_ptr<Class> Class##WeakPtr
typedef std::shared_ptr<Class> Class##SharedPtr; \
typedef std::shared_ptr<const Class> Class##ConstSharedPtr; \
typedef std::weak_ptr<Class> Class##WeakPtr

namespace urdf{

// shared pointer used in joint.h
typedef boost::shared_ptr<double> DoubleSharedPtr;
typedef std::shared_ptr<double> DoubleSharedPtr;

URDF_TYPEDEF_CLASS_POINTER(Box);
URDF_TYPEDEF_CLASS_POINTER(Collision);
Expand All @@ -71,21 +69,21 @@ URDF_TYPEDEF_CLASS_POINTER(Visual);

// create *_pointer_cast functions in urdf namespace
template<class T, class U>
boost::shared_ptr<T> const_pointer_cast(boost::shared_ptr<U> const & r)
std::shared_ptr<T> const_pointer_cast(std::shared_ptr<U> const & r)
{
return boost::const_pointer_cast<T>(r);
return std::const_pointer_cast<T>(r);
}

template<class T, class U>
boost::shared_ptr<T> dynamic_pointer_cast(boost::shared_ptr<U> const & r)
std::shared_ptr<T> dynamic_pointer_cast(std::shared_ptr<U> const & r)
{
return boost::dynamic_pointer_cast<T>(r);
return std::dynamic_pointer_cast<T>(r);
}

template<class T, class U>
boost::shared_ptr<T> static_pointer_cast(boost::shared_ptr<U> const & r)
std::shared_ptr<T> static_pointer_cast(std::shared_ptr<U> const & r)
{
return boost::static_pointer_cast<T>(r);
return std::static_pointer_cast<T>(r);
}

}
Expand Down
67 changes: 67 additions & 0 deletions urdf_model/include/urdf_model/utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2016, Open Source Robotics Foundation (OSRF)
* All rights reserved.
*
* 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 OSRF 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 OWNER 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: Steve Peters */

#ifndef URDF_INTERFACE_UTILS_H
#define URDF_INTERFACE_UTILS_H

#include <string>
#include <vector>

namespace urdf {

// Replacement for boost::split( ... , ... , boost::is_any_of(" "))
inline
void split_string(std::vector<std::string> &result,
const std::string &input,
const std::string &isAnyOf)
{
std::string::size_type start = 0;
std::string::size_type end = input.find_first_of(isAnyOf, start);
while (end != std::string::npos)
{
result.push_back(input.substr(start, end-start));
start = end + 1;
end = input.find_first_of(isAnyOf, start);
}
if (start < input.length())
{
result.push_back(input.substr(start));
}
}

}

#endif
4 changes: 2 additions & 2 deletions urdf_model_state/include/urdf_model_state/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,15 @@
#ifndef URDF_MODEL_STATE_TYPES_H
#define URDF_MODEL_STATE_TYPES_H

#include <boost/shared_ptr.hpp>
#include <memory>


namespace urdf{

class JointState;

// typedef shared pointers
typedef boost::shared_ptr<JointState> JointStateSharedPtr;
typedef std::shared_ptr<JointState> JointStateSharedPtr;

}

Expand Down
4 changes: 2 additions & 2 deletions urdf_sensor/include/urdf_sensor/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,15 @@
#ifndef URDF_SENSOR_TYPES_H
#define URDF_SENSOR_TYPES_H

#include <boost/shared_ptr.hpp>
#include <memory>


namespace urdf{

class VisualSensor;

// typedef shared pointers
typedef boost::shared_ptr<VisualSensor> VisualSensorSharedPtr;
typedef std::shared_ptr<VisualSensor> VisualSensorSharedPtr;

}

Expand Down
4 changes: 2 additions & 2 deletions urdf_world/include/urdf_world/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,15 @@
#ifndef URDF_WORLD_TYPES_H
#define URDF_WORLD_TYPES_H

#include <boost/shared_ptr.hpp>
#include <memory>


namespace urdf{

class ModelInterface;

// typedef shared pointers
typedef boost::shared_ptr<ModelInterface> ModelInterfaceSharedPtr;
typedef std::shared_ptr<ModelInterface> ModelInterfaceSharedPtr;

}

Expand Down

0 comments on commit 5cb0b6b

Please sign in to comment.