Skip to content

Commit

Permalink
Merge pull request #129 from Pandhariix/melodic_compatibility
Browse files Browse the repository at this point in the history
Melodic compatibility
  • Loading branch information
Maxime Busy committed Jan 8, 2020
2 parents 1758a83 + 6a09f9c commit d528305
Show file tree
Hide file tree
Showing 5 changed files with 5 additions and 6 deletions.
4 changes: 0 additions & 4 deletions CMakeLists_catkin.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,6 @@ add_definitions(-DLIBQI_VERSION=${naoqi_libqi_VERSION_MAJOR}${naoqi_libqi_VERSIO

catkin_package(LIBRARIES naoqi_driver_module naoqi_driver)

if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror=deprecated-declarations")
endif()

include_directories( include ${catkin_INCLUDE_DIRS})

# create the different libraries
Expand Down
2 changes: 1 addition & 1 deletion src/converters/joint_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void JointStateConverter::reset()

// set mimic joint list
mimic_.clear();
for(std::map< std::string, boost::shared_ptr< urdf::Joint > >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++){
for(std::map< std::string, urdf::JointSharedPtr >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++){
if(i->second->mimic){
mimic_.insert(make_pair(i->first, i->second->mimic));
}
Expand Down
2 changes: 1 addition & 1 deletion src/converters/joint_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class JointStateConverter : public BaseConverter<JointStateConverter>

typedef boost::shared_ptr<tf2_ros::Buffer> BufferPtr;

typedef std::map<std::string, boost::shared_ptr<urdf::JointMimic> > MimicMap;
typedef std::map<std::string, urdf::JointMimicSharedPtr> MimicMap;

public:
JointStateConverter( const std::string& name, const float& frequency, const BufferPtr& tf2_buffer, const qi::SessionPtr& session );
Expand Down
1 change: 1 addition & 0 deletions src/helpers/filesystem_helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#ifndef FILESYSTEM_HELPERS_HPP
#define FILESYSTEM_HELPERS_HPP

#include <iostream>
#include <qi/session.hpp>

#include <boost/filesystem.hpp>
Expand Down
2 changes: 2 additions & 0 deletions src/tools/from_any_value.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#ifndef FROM_ANY_VALUE_HPP
#define FROM_ANY_VALUE_HPP

#include <iostream>

/*
* LOCAL includes
*/
Expand Down

0 comments on commit d528305

Please sign in to comment.