From f09d9ed044f0c241856a922756d69f28b10f025d Mon Sep 17 00:00:00 2001 From: Olivier Stasse <ostasse@laas.fr> Date: Mon, 18 Jan 2016 18:20:05 +0100 Subject: [PATCH] Fix warnings + missing library. --- CMakeLists.txt | 2 +- include/dynamic_graph_bridge/ros_interpreter.hh | 2 -- src/robot_model.cpp | 2 +- src/ros_interpreter.cpp | 7 ------- src/sot_loader.cpp | 14 ++++++++------ src/sot_loader.hh | 5 +++-- 6 files changed, 13 insertions(+), 19 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b0f781d..ac768ed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -150,7 +150,7 @@ pkg_config_use_dependency(interpreter dynamic_graph_bridge_msgs) # Stand alone embedded intepreter with a robot controller. add_executable(geometric_simu src/geometric_simu.cpp src/sot_loader.cpp) pkg_config_use_dependency(geometric_simu roscpp) -target_link_libraries(geometric_simu ${Boost_LIBRARIES} dl) +target_link_libraries(geometric_simu ros_bridge ${Boost_LIBRARIES} dl) add_subdirectory(src) diff --git a/include/dynamic_graph_bridge/ros_interpreter.hh b/include/dynamic_graph_bridge/ros_interpreter.hh index df1047a..1c8dec1 100644 --- a/include/dynamic_graph_bridge/ros_interpreter.hh +++ b/include/dynamic_graph_bridge/ros_interpreter.hh @@ -28,8 +28,6 @@ namespace dynamicgraph explicit Interpreter (ros::NodeHandle& nodeHandle); - /// \brief Run a command and return result. - std::string runCommand (const std::string& command) __attribute__ ((deprecated)); /// \brief Method to start python interpreter and deal with messages. /// \param Command string to execute, result, stdout, stderr strings. void runCommand(const std::string & command, std::string &result, diff --git a/src/robot_model.cpp b/src/robot_model.cpp index f27cdf6..44911ea 100644 --- a/src/robot_model.cpp +++ b/src/robot_model.cpp @@ -112,7 +112,7 @@ vectorN convertVector(const ml::Vector& v) ml::Vector convertVector(const vectorN& v) { ml::Vector res; - res.resize(v.size()); + res.resize((unsigned int)v.size()); for (unsigned i = 0; i < v.size(); ++i) res(i) = v[i]; return res; diff --git a/src/ros_interpreter.cpp b/src/ros_interpreter.cpp index e4f572f..c4d58fd 100644 --- a/src/ros_interpreter.cpp +++ b/src/ros_interpreter.cpp @@ -43,13 +43,6 @@ namespace dynamicgraph return true; } - std::string - Interpreter::runCommand - (const std::string& command) - { - return interpreter_.python(command); - } - void Interpreter::runCommand (const std::string & command, std::string &result, diff --git a/src/sot_loader.cpp b/src/sot_loader.cpp index 375977a..d347064 100644 --- a/src/sot_loader.cpp +++ b/src/sot_loader.cpp @@ -176,8 +176,10 @@ void SotLoader::Initialization() // Load the symbols. createSotExternalInterface_t * createSot = - (createSotExternalInterface_t *) dlsym(SotRobotControllerLibrary, - "createSotExternalInterface"); + reinterpret_cast<createSotExternalInterface_t *> + (reinterpret_cast<long> + (dlsym(SotRobotControllerLibrary, + "createSotExternalInterface"))); const char* dlsym_error = dlerror(); if (dlsym_error) { std::cerr << "Cannot load symbol create: " << dlsym_error << '\n'; @@ -256,15 +258,15 @@ void SotLoader::oneIteration() } -bool SotLoader::start_dg(std_srvs::Empty::Request& request, - std_srvs::Empty::Response& response) +bool SotLoader::start_dg(std_srvs::Empty::Request& , + std_srvs::Empty::Response& ) { dynamic_graph_stopped_=false; return true; } -bool SotLoader::stop_dg(std_srvs::Empty::Request& request, - std_srvs::Empty::Response& response) +bool SotLoader::stop_dg(std_srvs::Empty::Request& , + std_srvs::Empty::Response& ) { dynamic_graph_stopped_ = true; return true; diff --git a/src/sot_loader.hh b/src/sot_loader.hh index 2d02679..64d5ed3 100644 --- a/src/sot_loader.hh +++ b/src/sot_loader.hh @@ -85,7 +85,8 @@ protected: XmlRpc::XmlRpcValue stateVectorMap_; /// \brief List of parallel joints from the state vector. - std::vector<int> parallel_joints_to_state_vector_; + typedef std::vector<int> parallel_joints_to_state_vector_t; + parallel_joints_to_state_vector_t parallel_joints_to_state_vector_; /// \brief Coefficient between parallel joints and the state vector. std::vector<double> coefficient_parallel_joints_; @@ -98,7 +99,7 @@ protected: // Number of DOFs according to KDL. int nbOfJoints_; - int nbOfParallelJoints_; + parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_; public: -- GitLab