Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • gsaurel/dynamic_graph_bridge
  • stack-of-tasks/dynamic_graph_bridge
2 results
Show changes
Commits on Source (302)
Showing
with 539 additions and 395 deletions
# format (Guilhem Saurel, 2022-09-06)
426c21a7f4e5b445d17825235f983e2f8e1a86ec
include: http://rainboard.laas.fr/project/dynamic_graph_bridge/.gitlab-ci.yml
[submodule "cmake"] [submodule "cmake"]
path = cmake path = cmake
url = git://github.com/jrl-umi3218/jrl-cmakemodules.git url = https://github.com/jrl-umi3218/jrl-cmakemodules.git
ci:
autoupdate_branch: 'devel'
repos:
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v14.0.6
hooks:
- id: clang-format
args: [--style=Google]
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.3.0
hooks:
- id: check-added-large-files
- id: check-ast
- id: check-executables-have-shebangs
- id: check-json
- id: check-merge-conflict
- id: check-symlinks
- id: check-toml
- id: check-yaml
- id: debug-statements
- id: destroyed-symlinks
- id: detect-private-key
- id: end-of-file-fixer
- id: fix-byte-order-marker
- id: mixed-line-ending
- id: trailing-whitespace
- repo: https://github.com/psf/black
rev: 22.8.0
hooks:
- id: black
- repo: https://github.com/PyCQA/flake8
rev: 5.0.4
hooks:
- id: flake8
- repo: https://github.com/cheshirekow/cmake-format-precommit
rev: v0.6.13
hooks:
- id: cmake-format
# Copyright (C) 2008-2013 LAAS-CNRS, JRL AIST-CNRS. # Copyright (C) 2008-2020 LAAS-CNRS, JRL AIST-CNRS.
# #
# Author: Florent Lamiraux, Nirmal Giftsun # Author: Florent Lamiraux, Nirmal Giftsun, Guilhem Saurel
# #
# This program is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation, either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
# GNU General Public License for more details.
#
# You should have received a copy of the GNU General Public License
# along with this program. If not, see <http://www.gnu.org/licenses/>.
# Catkin part
cmake_minimum_required(VERSION 2.4.6) cmake_minimum_required(VERSION 3.1)
project(dynamic_graph_bridge) # Project properties
set(PROJECT_ORG stack-of-tasks)
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation std_srvs geometry_msgs sensor_msgs tf) set(PROJECT_NAME dynamic_graph_bridge)
find_package(realtime_tools) set(PROJECT_DESCRIPTION "Dynamic graph bridge library")
find_package(Boost REQUIRED COMPONENTS program_options) set(PROJECT_URL "https://github.com/${PROJECT_ORG}/${PROJECT_NAME}")
# Project options
option(BUILD_PYTHON_INTERFACE "Build the python bindings" ON)
## LAAS cmake submodule part # Project configuration
set(PROJECT_DESCRIPTION "Dynamic graph bridge library") set(PROJECT_USE_CMAKE_EXPORT TRUE)
set(PROJECT_NAME dynamic_graph_bridge) set(CUSTOM_HEADER_DIR ${PROJECT_NAME})
set(PROJECT_URL "") set(CXX_DISABLE_WERROR FALSE)
set(DOXYGEN_USE_MATHJAX YES)
set(CATKIN_ENABLE_TESTING OFF)
set(CXX_DISABLE_WERROR False) # JRL-cmakemodule setup
set(CUSTOM_HEADER_DIR dynamic_graph_bridge)
set(${PROJECT_NAME}_HEADERS
include/dynamic_graph_bridge/ros_init.hh
include/dynamic_graph_bridge/ros_interpreter.hh
include/dynamic_graph_bridge/sot_loader.hh
)
include(cmake/base.cmake) include(cmake/base.cmake)
include(cmake/boost.cmake)
include(cmake/ros.cmake) include(cmake/ros.cmake)
include(cmake/GNUInstallDirs.cmake)
include(cmake/python.cmake)
SETUP_PROJECT()
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_BINARY_DIR}/bin)
set(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR}/lib)
set(CMAKE_INSTALL_RPATH "${LIBRARY_OUTPUT_PATH}")
set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${LIBRARY_OUTPUT_PATH}")
set(PKG_CONFIG_ADDITIONAL_VARIABLES
${PKG_CONFIG_ADDITIONAL_VARIABLES}
plugindirname
plugindir
)
add_required_dependency(roscpp)
add_required_dependency("realtime_tools >= 1.8")
add_required_dependency(bullet)
add_required_dependency(jrl-mal)
add_required_dependency(dynamic-graph)
add_required_dependency(dynamic-graph-python)
add_required_dependency(sot-core)
add_required_dependency(sot-dynamic)
add_required_dependency(jrl-dynamics-urdf)
add_required_dependency(dynamic_graph_bridge_msgs)
add_library(ros_bridge
src/converter.hh
include/dynamic_graph_bridge/ros_init.hh src/ros_init.cpp
src/sot_to_ros.hh src/sot_to_ros.cpp
)
pkg_config_use_dependency(ros_bridge jrl-mal)
pkg_config_use_dependency(ros_bridge bullet)
pkg_config_use_dependency(ros_bridge dynamic_graph_bridge_msgs)
install(TARGETS ros_bridge DESTINATION lib)
# Add ros_bridge in the dynamic-graph-bridge pkg-config file.
# Make sure rpath are preserved during the install as ROS dependencies
# are not installed.
set_target_properties(ros_bridge PROPERTIES BUILD_WITH_INSTALL_RPATH True
LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/lib)
macro(compile_plugin NAME)
message(lib path ${LIBRARY_OUTPUT_PATH})
file(MAKE_DIRECTORY "${LIBRARY_OUTPUT_PATH}/dynamic_graph/ros/${NAME}")
add_library(${NAME} src/${NAME}.cpp src/${NAME}.hh)
pkg_config_use_dependency(${NAME} jrl-mal)
pkg_config_use_dependency(${NAME} dynamic-graph)
pkg_config_use_dependency(${NAME} sot-core)
pkg_config_use_dependency(${NAME} jrl-dynamics-urdf)
pkg_config_use_dependency(${NAME} dynamic_graph_bridge_msgs)
add_dependencies(${NAME} ros_bridge)
target_link_libraries(${NAME} ros_bridge)
set_target_properties(${NAME} PROPERTIES BUILD_WITH_INSTALL_RPATH True)
install(TARGETS ${NAME} DESTINATION lib)
dynamic_graph_python_module("ros/${NAME}"
${NAME}
ros/${NAME}/wrap
)
PKG_CONFIG_USE_DEPENDENCY(ros/${NAME}/wrap realtime_tools)
PKG_CONFIG_USE_DEPENDENCY(ros/${NAME}/wrap jrl-mal)
PKG_CONFIG_USE_DEPENDENCY(ros/${NAME}/wrap dynamic_graph)
PKG_CONFIG_USE_DEPENDENCY(ros/${NAME}/wrap sot-core)
PKG_CONFIG_USE_DEPENDENCY(ros/${NAME}/wrap dynamic_graph_bridge_msgs)
endmacro()
include(cmake/python.cmake)
compile_plugin(ros_publish)
compile_plugin(ros_subscribe)
compile_plugin(ros_time)
compile_plugin(ros_joint_state)
target_link_libraries(ros_joint_state "${DYNAMIC_GRAPH_PLUGINDIR}/dynamic.so")
compile_plugin(robot_model)
# ros_interperter library.
add_library(ros_interpreter src/ros_interpreter.cpp)
pkg_config_use_dependency(ros_interpreter jrl-mal)
pkg_config_use_dependency(ros_interpreter dynamic-graph)
pkg_config_use_dependency(ros_interpreter sot-core)
pkg_config_use_dependency(ros_interpreter roscpp)
pkg_config_use_dependency(ros_interpreter dynamic_graph_bridge_msgs)
add_dependencies(ros_interpreter ros_bridge)
target_link_libraries(ros_interpreter ros_bridge)
set_target_properties(ros_interpreter PROPERTIES BUILD_WITH_INSTALL_RPATH True
LIBRARY_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/lib)
message(cmakeinstalllibdir " is ${CMAKE_INSTALL_LIBDIR} ")
install(TARGETS ros_interpreter DESTINATION lib)
# Stand alone remote dynamic-graph Python interpreter.
add_executable(interpreter src/interpreter.cpp)
add_dependencies(interpreter ros_interpreter)
target_link_libraries(interpreter ros_interpreter)
pkg_config_use_dependency(interpreter jrl-mal)
pkg_config_use_dependency(interpreter dynamic-graph)
pkg_config_use_dependency(interpreter sot-core)
pkg_config_use_dependency(interpreter sot-dynamic)
pkg_config_use_dependency(interpreter dynamic_graph_bridge_msgs)
# set_target_properties(interpreter PROPERTIES BUILD_WITH_INSTALL_RPATH True)
#install(TARGETS interpreter DESTINATION bin)
# 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 ros_bridge ${Boost_LIBRARIES} dl)
# Sot loader library
add_library(sot_loader src/sot_loader.cpp)
pkg_config_use_dependency(sot_loader dynamic-graph)
pkg_config_use_dependency(sot_loader sot-core)
target_link_libraries(sot_loader ${Boost_LIBRARIES})
install(TARGETS sot_loader DESTINATION lib)
# Project definition
compute_project_args(PROJECT_ARGS LANGUAGES CXX)
project(${PROJECT_NAME} ${PROJECT_ARGS})
# Project dependencies
set(CATKIN_REQUIRED_COMPONENTS
roscpp
std_msgs
message_generation
std_srvs
geometry_msgs
sensor_msgs
tf2_ros
realtime_tools)
if(BUILD_PYTHON_INTERFACE)
add_project_dependency(dynamic-graph-python 4.0.0 REQUIRED)
string(REGEX REPLACE "-" "_" PY_NAME ${PROJECT_NAME})
set(CATKIN_REQUIRED_COMPONENTS ${CATKIN_REQUIRED_COMPONENTS} rospy)
endif(BUILD_PYTHON_INTERFACE)
add_project_dependency(Boost REQUIRED COMPONENTS program_options)
add_project_dependency(dynamic_graph_bridge_msgs 0.3.0 REQUIRED)
add_project_dependency(sot-core REQUIRED)
if(Boost_VERSION GREATER 107299 OR Boost_VERSION_MACRO GREATER 107299)
# Silence a warning about a deprecated use of boost bind by boost >= 1.73
# without dropping support for boost < 1.73
add_definitions(-DBOOST_BIND_GLOBAL_PLACEHOLDERS)
endif()
find_package(catkin REQUIRED COMPONENTS ${CATKIN_REQUIRED_COMPONENTS})
# Main Library
set(${PROJECT_NAME}_HEADERS
include/${PROJECT_NAME}/fwd.hh
include/${PROJECT_NAME}/ros_init.hh
include/${PROJECT_NAME}/sot_loader.hh
include/${PROJECT_NAME}/sot_loader_basic.hh
include/${PROJECT_NAME}/ros_interpreter.hh
src/converter.hh
src/sot_to_ros.hh)
set(${PROJECT_NAME}_SOURCES src/ros_init.cpp src/sot_to_ros.cpp
src/ros_parameter.cpp)
add_library(ros_bridge SHARED ${${PROJECT_NAME}_SOURCES}
${${PROJECT_NAME}_HEADERS})
target_include_directories(ros_bridge SYSTEM PUBLIC ${catkin_INCLUDE_DIRS})
target_include_directories(ros_bridge PUBLIC $<INSTALL_INTERFACE:include>)
target_link_libraries(
ros_bridge ${catkin_LIBRARIES} sot-core::sot-core pinocchio::pinocchio
dynamic_graph_bridge_msgs::dynamic_graph_bridge_msgs)
if(SUFFIX_SO_VERSION)
set_target_properties(ros_bridge PROPERTIES SOVERSION ${PROJECT_VERSION})
endif(SUFFIX_SO_VERSION)
if(NOT INSTALL_PYTHON_INTERFACE_ONLY)
install(
TARGETS ros_bridge
EXPORT ${TARGETS_EXPORT_NAME}
DESTINATION lib)
endif(NOT INSTALL_PYTHON_INTERFACE_ONLY)
add_subdirectory(src) add_subdirectory(src)
add_subdirectory(tests)
# Deal with the ROS part. # install ros executables
add_service_files( FILES RunPythonFile.srv ) install(PROGRAMS scripts/robot_pose_publisher scripts/run_command
generate_messages( DEPENDENCIES std_msgs ) scripts/tf_publisher DESTINATION share/${PROJECT_NAME})
catkin_package(CATKIN_DEPENDS message_runtime LIBRARIES ros_bridge ros_interpreter)
# Add libraries in pc file generated by cmake submodule
PKG_CONFIG_APPEND_LIBS(ros_bridge ros_interpreter)
#install ros executables
install(PROGRAMS
${CMAKE_SOURCE_DIR}/scripts/robot_pose_publisher
${CMAKE_SOURCE_DIR}/scripts/run_command
${CMAKE_SOURCE_DIR}/scripts/tf_publisher
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
message(cmake_install_bindir " is ${CMAKE_INSTALL_BINDIR} ")
install(TARGETS geometric_simu DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
install(FILES manifest.xml DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/)
# Service file.
install(FILES ./srv/RunPythonFile.srv DESTINATION ${CMAKE_INSTALL_PREFIX}/share/${PROJECT_NAME}/srv)
SETUP_PROJECT_FINALIZE()
# Install package information
install(FILES manifest.xml package.xml DESTINATION share/${PROJECT_NAME})
BSD 2-Clause License
Copyright (c) 2019, CNRS
Author: Stack of Tasks Development Team
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.
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.
dynamic-graph bindings # Dynamic Graph bindings
======================
[![Pipeline status](https://gitlab.laas.fr/stack-of-tasks/dynamic_graph_bridge/badges/master/pipeline.svg)](https://gitlab.laas.fr/stack-of-tasks/dynamic_graph_bridge/commits/master)
[![Coverage report](https://gitlab.laas.fr/stack-of-tasks/dynamic_graph_bridge/badges/master/coverage.svg?job=doc-coverage)](https://gepettoweb.laas.fr/doc/stack-of-tasks/dynamic_graph_bridge/master/coverage/)
[![Code style: black](https://img.shields.io/badge/code%20style-black-000000.svg)](https://github.com/psf/black)
[![pre-commit.ci status](https://results.pre-commit.ci/badge/github/stack-of-tasks/dynamic_graph_bridge/master.svg)](https://results.pre-commit.ci/latest/github/stack-of-tasks/dynamic_graph_bridge)
This ROS package binds together the ROS framework with the This ROS package binds together the ROS framework with the
dynamic-graph real-time control architecture. dynamic-graph real-time control architecture.
Subproject commit fa2738146fa19d8bbbb1d8c8a97a2b4809ce81af Subproject commit 57c46b2d7b26bb0c25f8f98cfc2a9868e03be603
INPUT = @PROJECT_SOURCE_DIR@/include \ INPUT = @PROJECT_SOURCE_DIR@/include \
@PROJECT_SOURCE_DIR@/doc @PROJECT_SOURCE_DIR@/doc
/*
* Copyright CNRS 2021
*
* Author: Florent Lamiraux
*
* This file is part of sot-core.
*/
#ifndef DYNAMIC_GRAPH_BRIDGE_FWD_HH
#define DYNAMIC_GRAPH_BRIDGE_FWD_HH
#include <dynamic-graph/fwd.hh>
namespace dynamicgraph {
// classes defined in sot-core
class Interpreter;
typedef std::shared_ptr<Interpreter> InterpreterPtr_t;
} // namespace dynamicgraph
#endif // DYNAMIC_GRAPH_PYTHON_FWD_HH
#ifndef ROS_INIT_HH #ifndef ROS_INIT_HH
# define ROS_INIT_HH #define ROS_INIT_HH
# include <ros/ros.h> #include <ros/ros.h>
namespace dynamicgraph namespace dynamicgraph {
{ ros::NodeHandle& rosInit(bool createAsyncSpinner = false,
ros::NodeHandle& rosInit (bool createAsyncSpinner=false, bool createMultiThreadSpinner=true); bool createMultiThreadSpinner = true);
/// \brief Return spinner or throw an exception if spinner /// \brief Return spinner or throw an exception if spinner
/// creation has been disabled at startup. /// creation has been disabled at startup.
ros::AsyncSpinner& spinner (); ros::AsyncSpinner& spinner();
/// \brief Return multi threaded spinner or throw an exception if spinner /// \brief Return multi threaded spinner or throw an exception if spinner
/// creation has been disabled at startup. /// creation has been disabled at startup.
ros::MultiThreadedSpinner& mtSpinner (); ros::MultiThreadedSpinner& mtSpinner();
} // end of namespace dynamicgraph.
} // end of namespace dynamicgraph. #endif //! ROS_INIT_HH
#endif //! ROS_INIT_HH
#ifndef DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH #ifndef DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH
# define DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH #define DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH
# include <ros/ros.h> #pragma GCC diagnostic push
# include <dynamic_graph_bridge_msgs/RunCommand.h> #pragma GCC system_header
# include <dynamic_graph_bridge_msgs/RunPythonFile.h> #include <ros/ros.h>
# include <dynamic-graph/python/interpreter.hh> #pragma GCC diagnostic pop
namespace dynamicgraph #include <dynamic_graph_bridge_msgs/RunCommand.h>
{ #include <dynamic_graph_bridge_msgs/RunPythonFile.h>
/// \brief This class wraps the implementation of the runCommand
/// service. #include <dynamic-graph/python/interpreter.hh>
/// #include <dynamic_graph_bridge/fwd.hh>
/// This takes as input a ROS node handle and do not handle the
/// callback so that the service behavior can be controlled from namespace dynamicgraph {
/// the outside. /// \brief This class wraps the implementation of the runCommand
class Interpreter /// service.
{ ///
public: /// This takes as input a ROS node handle and do not handle the
typedef boost::function< /// callback so that the service behavior can be controlled from
bool (dynamic_graph_bridge_msgs::RunCommand::Request&, /// the outside.
dynamic_graph_bridge_msgs::RunCommand::Response&)> class Interpreter {
runCommandCallback_t; public:
typedef boost::function<bool(
typedef boost::function< dynamic_graph_bridge_msgs::RunCommand::Request&,
bool (dynamic_graph_bridge_msgs::RunPythonFile::Request&, dynamic_graph_bridge_msgs::RunCommand::Response&)>
dynamic_graph_bridge_msgs::RunPythonFile::Response&)> runCommandCallback_t;
runPythonFileCallback_t;
typedef boost::function<bool(
explicit Interpreter (ros::NodeHandle& nodeHandle); dynamic_graph_bridge_msgs::RunPythonFile::Request&,
dynamic_graph_bridge_msgs::RunPythonFile::Response&)>
/// \brief Method to start python interpreter and deal with messages. runPythonFileCallback_t;
/// \param Command string to execute, result, stdout, stderr strings.
void runCommand(const std::string & command, std::string &result, explicit Interpreter(ros::NodeHandle& nodeHandle);
std::string &out, std::string &err);
/// \brief Method to start python interpreter and deal with messages.
/// \brief Method to parse python scripts. /// \param Command string to execute, result, stdout, stderr strings.
/// \param Input file name to parse. void runCommand(const std::string& command, std::string& result,
void runPythonFile(std::string ifilename); std::string& out, std::string& err);
/// Initialize service run_command /// \brief Method to parse python scripts.
void startRosService (); /// \param Input file name to parse.
void runPythonFile(std::string ifilename);
protected:
/// \brief Run a Python command and return result, stderr and stdout. /// Initialize service run_command
bool runCommandCallback (dynamic_graph_bridge_msgs::RunCommand::Request& req, void startRosService();
dynamic_graph_bridge_msgs::RunCommand::Response& res);
protected:
/// \brief Run a Python file. /// \brief Run a Python command and return result, stderr and stdout.
bool runPythonFileCallback (dynamic_graph_bridge_msgs::RunPythonFile::Request& req, bool runCommandCallback(dynamic_graph_bridge_msgs::RunCommand::Request& req,
dynamic_graph_bridge_msgs::RunPythonFile::Response& res); dynamic_graph_bridge_msgs::RunCommand::Response& res);
private: /// \brief Run a Python file.
python::Interpreter interpreter_; bool runPythonFileCallback(
ros::NodeHandle& nodeHandle_; dynamic_graph_bridge_msgs::RunPythonFile::Request& req,
ros::ServiceServer runCommandSrv_; dynamic_graph_bridge_msgs::RunPythonFile::Response& res);
ros::ServiceServer runPythonFileSrv_;
}; private:
} // end of namespace dynamicgraph. python::Interpreter interpreter_;
ros::NodeHandle& nodeHandle_;
#endif //! DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH ros::ServiceServer runCommandSrv_;
ros::ServiceServer runPythonFileSrv_;
};
} // end of namespace dynamicgraph.
#endif //! DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH
#ifndef _ROS_DYNAMIC_GRAPH_PARAMETER_
#define _ROS_DYNAMIC_GRAPH_PARAMETER_
namespace dynamicgraph {
bool parameter_server_read_robot_description();
}
#endif /* _ROS_DYNAMIC_GRAPH_PARAMETER_ */
/* /*
* Copyright 2011, * Copyright 2016,
* Olivier Stasse, * Olivier Stasse,
* *
* CNRS * CNRS
* *
* This file is part of sot-core.
* sot-core is free software: you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public License
* as published by the Free Software Foundation, either version 3 of
* the License, or (at your option) any later version.
* sot-core is distributed in the hope that it will be
* useful, but WITHOUT ANY WARRANTY; without even the implied warranty
* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details. You should
* have received a copy of the GNU Lesser General Public License along
* with sot-core. If not, see <http://www.gnu.org/licenses/>.
*/ */
/* -------------------------------------------------------------------------- */ /* -------------------------------------------------------------------------- */
/* --- INCLUDES ------------------------------------------------------------- */ /* --- INCLUDES ------------------------------------------------------------- */
/* -------------------------------------------------------------------------- */ /* -------------------------------------------------------------------------- */
#ifndef _SOT_LOADER_HH_
#define _SOT_LOADER_HH_
// System includes // System includes
#include <iostream>
#include <cassert> #include <cassert>
// STL includes // STL includes
#include <map> #include <map>
// Pinocchio includes
#include <pinocchio/fwd.hpp>
// Boost includes // Boost includes
#include <boost/program_options.hpp>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/format.hpp> #include <boost/format.hpp>
#include <boost/program_options.hpp>
#include <boost/thread/thread.hpp>
// ROS includes // ROS includes
#include <sensor_msgs/JointState.h>
#include <tf2_ros/transform_broadcaster.h>
#include "ros/ros.h" #include "ros/ros.h"
#include "std_srvs/Empty.h" #include "std_srvs/Empty.h"
#include <sensor_msgs/JointState.h>
// Sot Framework includes // Sot Framework includes
#include <sot/core/debug.hh>
#include <sot/core/abstract-sot-external-interface.hh> #include <sot/core/abstract-sot-external-interface.hh>
#include <sot/core/debug.hh>
// Dynamic-graph-bridge includes.
#include <dynamic_graph_bridge/sot_loader_basic.hh>
namespace po = boost::program_options; namespace po = boost::program_options;
namespace dgs = dynamicgraph::sot; namespace dgs = dynamicgraph::sot;
class SotLoader : public SotLoaderBasic {
class SotLoader { protected:
protected:
// Dynamic graph is stopped.
bool dynamic_graph_stopped_;
/// \brief the sot-hrp2 controller
dgs::AbstractSotExternalInterface * sotController_;
po::variables_map vm_;
std::string dynamicLibraryName_;
/// Map of sensor readings /// Map of sensor readings
std::map <std::string,dgs::SensorValues> sensorsIn_; std::map<std::string, dgs::SensorValues> sensorsIn_;
/// Map of control values /// Map of control values
std::map<std::string,dgs::ControlValues> controlValues_; std::map<std::string, dgs::ControlValues> controlValues_;
/// Angular values read by encoders /// Angular values read by encoders
std::vector <double> angleEncoder_; std::vector<double> angleEncoder_;
/// Angular values sent to motors /// Angular values sent to motors
std::vector<double> angleControl_; std::vector<double> angleControl_;
/// Forces read by force sensors /// Forces read by force sensors
...@@ -74,75 +62,42 @@ protected: ...@@ -74,75 +62,42 @@ protected:
/// Attitude of the robot computed by extended Kalman filter. /// Attitude of the robot computed by extended Kalman filter.
std::vector<double> baseAtt_; std::vector<double> baseAtt_;
/// Accelerations read by Accelerometers /// Accelerations read by Accelerometers
std::vector <double> accelerometer_; std::vector<double> accelerometer_;
/// Angular velocity read by gyrometers /// Angular velocity read by gyrometers
std::vector <double> gyrometer_; std::vector<double> gyrometer_;
/// URDF string description of the robot. /// URDF string description of the robot.
std::string robot_desc_string_; std::string robot_desc_string_;
/// \brief Map between SoT state vector and some joint_state_links
XmlRpc::XmlRpcValue stateVectorMap_;
/// \brief List of parallel joints from the 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_;
// Joint state publication. /// The thread running dynamic graph
ros::Publisher joint_pub_; boost::thread thread_;
// Joint state to be published.
sensor_msgs::JointState joint_state_;
// Number of DOFs according to KDL. // \brief Start control loop
int nbOfJoints_; virtual void startControlLoop();
parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_;
// Robot Pose Publisher
tf2_ros::TransformBroadcaster freeFlyerPublisher_;
geometry_msgs::TransformStamped freeFlyerPose_;
public: public:
SotLoader(); SotLoader();
~SotLoader() {}; ~SotLoader();
// \brief Read user input to extract the path of the SoT dynamic library. // \brief Create a thread for ROS and start the control loop.
int parseOptions(int argc, char *argv[]); void initializeRosNode(int argc, char *argv[]);
// \brief Load the SoT
void Initialization();
// \brief Compute one iteration of control. // \brief Compute one iteration of control.
// Basically calls fillSensors, the SoT and the readControl. // Basically calls fillSensors, the SoT and the readControl.
void oneIteration(); void oneIteration();
// \brief Fill the sensors value for the SoT. // \brief Fill the sensors value for the SoT.
void fillSensors(std::map<std::string, void fillSensors(std::map<std::string, dgs::SensorValues> &sensorsIn);
dgs::SensorValues> & sensorsIn);
// \brief Read the control computed by the SoT framework. // \brief Read the control computed by the SoT framework.
void readControl(std::map<std::string, void readControl(std::map<std::string, dgs::ControlValues> &controlValues);
dgs::ControlValues> & controlValues);
// \brief Prepare the SoT framework. // \brief Prepare the SoT framework.
void setup(); void setup();
// \brief Callback function when starting dynamic graph.
bool start_dg(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response);
// \brief Callback function when stopping dynamic graph.
bool stop_dg(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response);
// \brief Read the state vector description based upon the robot links.
int readSotVectorStateParam();
// \brief Init publication of joint states.
int initPublication();
// \brief Get Status of dg.
bool isDynamicGraphStopped()
{ return dynamic_graph_stopped_; }
}; };
#endif /* SOT_LOADER_HH_ */
/*
* Copyright 2016,
* Olivier Stasse,
*
* CNRS
*
*/
/* -------------------------------------------------------------------------- */
/* --- INCLUDES ------------------------------------------------------------- */
/* -------------------------------------------------------------------------- */
#ifndef _SOT_LOADER_BASIC_HH_
#define _SOT_LOADER_BASIC_HH_
// System includes
#include <cassert>
// STL includes
#include <map>
// Pinocchio includes
#include <pinocchio/fwd.hpp>
// Boost includes
#include <boost/foreach.hpp>
#include <boost/format.hpp>
#include <boost/program_options.hpp>
// ROS includes
#include <sensor_msgs/JointState.h>
#include "ros/ros.h"
#include "std_srvs/Empty.h"
// Sot Framework includes
#include <sot/core/abstract-sot-external-interface.hh>
#include <sot/core/debug.hh>
namespace po = boost::program_options;
namespace dgs = dynamicgraph::sot;
class SotLoaderBasic {
protected:
// Dynamic graph is stopped.
bool dynamic_graph_stopped_;
/// \brief the sot-hrp2 controller
dgs::AbstractSotExternalInterface* sotController_;
po::variables_map vm_;
std::string dynamicLibraryName_;
/// \brief Handle on the SoT library.
void* sotRobotControllerLibrary_;
/// \brief Map between SoT state vector and some joint_state_links
XmlRpc::XmlRpcValue stateVectorMap_;
/// \brief List of parallel joints from the 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_;
/// Advertises start_dynamic_graph services
ros::ServiceServer service_start_;
/// Advertises stop_dynamic_graph services
ros::ServiceServer service_stop_;
// Joint state publication.
ros::Publisher joint_pub_;
// Joint state to be published.
sensor_msgs::JointState joint_state_;
// Number of DOFs according to KDL.
int nbOfJoints_;
parallel_joints_to_state_vector_t::size_type nbOfParallelJoints_;
public:
SotLoaderBasic();
~SotLoaderBasic(){};
// \brief Read user input to extract the path of the SoT dynamic library.
int parseOptions(int argc, char* argv[]);
/// \brief Load the SoT device corresponding to the robot.
void Initialization();
/// \brief Unload the library which handles the robot device.
void CleanUp();
// \brief Create a thread for ROS.
virtual void initializeRosNode(int argc, char* argv[]);
// \brief Callback function when starting dynamic graph.
bool start_dg(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response);
// \brief Callback function when stopping dynamic graph.
bool stop_dg(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response);
// \brief Read the state vector description based upon the robot links.
int readSotVectorStateParam();
// \brief Init publication of joint states.
int initPublication();
// \brief Get Status of dg.
bool isDynamicGraphStopped() { return dynamic_graph_stopped_; }
// \brief Specify the name of the dynamic library.
void setDynamicLibraryName(std::string& afilename);
};
#endif /* _SOT_LOADER_BASIC_HH_ */
<package> <package format="2">
<name>dynamic_graph_bridge</name> <name>dynamic_graph_bridge</name>
<version>2.0.5</version> <version>3.4.5</version>
<description> <description>
ROS bindings for dynamic graph. ROS bindings for dynamic graph.
</description> </description>
<maintainer email="hpp@laas.fr">hpp@laas.fr</maintainer> <maintainer email="guilhem.saurel@laas.fr">guilhem.saurel@laas.fr</maintainer>
<author email="hpp@laas.fr">hpp@laas.fr</author> <author email="hpp@laas.fr">hpp@laas.fr</author>
<license>LGPL</license> <license>LGPL</license>
...@@ -16,24 +16,36 @@ ...@@ -16,24 +16,36 @@
<rosdoc config="rosdoc.yaml" /> <rosdoc config="rosdoc.yaml" />
</export> </export>
<buildtool_depend>catkin</buildtool_depend> <buildtool_depend>catkin</buildtool_depend>
<build_depend>std_msgs</build_depend> <build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend> <build_depend>std_srvs</build_depend>
<build_depend>roscpp</build_depend> <build_depend>roscpp</build_depend>
<build_depend>geometry_msgs</build_depend> <build_depend>geometry_msgs</build_depend>
<build_depend>sensor_msgs</build_depend> <build_depend>sensor_msgs</build_depend>
<build_depend>tf</build_depend> <build_depend>tf2_ros</build_depend>
<build_depend>realtime_tools</build_depend> <build_depend>realtime_tools</build_depend>
<build_depend>message_generation</build_depend> <build_depend>message_generation</build_depend>
<build_depend>message_runtime</build_depend>
<build_depend>dynamic-graph</build_depend>
<build_depend>dynamic-graph-python</build_depend>
<build_depend>sot-core</build_depend>
<build_depend>sot-dynamic-pinocchio</build_depend>
<build_depend>dynamic_graph_bridge_msgs</build_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>std_srvs</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>realtime_tools</exec_depend>
<exec_depend>message_generation</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>dynamic-graph</exec_depend>
<exec_depend>dynamic-graph-python</exec_depend>
<exec_depend>sot-core</exec_depend>
<exec_depend>sot-dynamic-pinocchio</exec_depend>
<exec_depend>dynamic_graph_bridge_msgs</exec_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>realtime_tools</run_depend>
<run_depend>message_runtime</run_depend>
</package> </package>
[tool.black]
exclude = "cmake"
...@@ -8,22 +8,26 @@ import rospy ...@@ -8,22 +8,26 @@ import rospy
import tf import tf
import sensor_msgs.msg import sensor_msgs.msg
frame = '' frame = ""
childFrame = '' childFrame = ""
def pose_broadcaster(msg): def pose_broadcaster(msg):
translation = msg.position[0:3]; # DEPRECATED. Robot Pose is already being published
rotation = tf.transformations.quaternion_from_euler(msg.position[3], msg.position[4], msg.position[5]) translation = msg.position[0:3]
rotation = tf.transformations.quaternion_from_euler(
msg.position[3], msg.position[4], msg.position[5]
)
tfbr = tf.TransformBroadcaster() tfbr = tf.TransformBroadcaster()
tfbr.sendTransform(translation, rotation, tfbr.sendTransform(translation, rotation, rospy.Time.now(), childFrame, frame)
rospy.Time.now(), childFrame, frame)
if __name__ == "__main__":
rospy.init_node("robot_pose_publisher", anonymous=True)
if __name__ == '__main__': frame = rospy.get_param("~frame", "odom")
rospy.init_node('robot_pose_publisher', anonymous=True) childFrame = rospy.get_param("~child_frame", "base_link")
topic = rospy.get_param("~topic", "joint_states")
frame = rospy.get_param('~frame', 'odom')
childFrame = rospy.get_param('~child_frame', 'base_link')
topic = rospy.get_param('~topic', 'joint_states')
rospy.Subscriber(topic, sensor_msgs.msg.JointState, pose_broadcaster) rospy.Subscriber(topic, sensor_msgs.msg.JointState, pose_broadcaster)
rospy.spin() rospy.spin()
...@@ -2,27 +2,59 @@ ...@@ -2,27 +2,59 @@
import rospy import rospy
import dynamic_graph # noqa: F401
import dynamic_graph_bridge_msgs.srv import dynamic_graph_bridge_msgs.srv
import sys import sys
import code import code
from code import InteractiveConsole from code import InteractiveConsole
import readline
import os
from dynamic_graph.ros.dgcompleter import DGCompleter
try:
import readline
except ImportError:
print("Module readline not available.")
# Enable a History
HISTFILE = "%s/.pyhistory" % os.environ["HOME"]
def savehist():
readline.write_history_file(HISTFILE)
class RosShell(InteractiveConsole): class RosShell(InteractiveConsole):
def __init__(self): def __init__(self):
self.cache = "" self.cache = ""
InteractiveConsole.__init__(self) InteractiveConsole.__init__(self)
rospy.loginfo('waiting for service...') rospy.loginfo("waiting for service...")
rospy.wait_for_service('run_command') rospy.wait_for_service("run_command")
self.client = rospy.ServiceProxy( self.client = rospy.ServiceProxy(
'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True) "run_command", dynamic_graph_bridge_msgs.srv.RunCommand, True
rospy.wait_for_service('run_script') )
rospy.wait_for_service("run_script")
self.scriptClient = rospy.ServiceProxy( self.scriptClient = rospy.ServiceProxy(
'run_script', dynamic_graph_bridge_msgs.srv.RunPythonFile, True) "run_script", dynamic_graph_bridge_msgs.srv.RunPythonFile, True
)
def runcode(self, code, retry = True): readline.set_completer(DGCompleter(self.client).complete)
readline.parse_and_bind("tab: complete")
# Read the existing history if there is one
if os.path.exists(HISTFILE):
readline.read_history_file(HISTFILE)
# Set maximum number of items that will be written to the history file
readline.set_history_length(300)
import atexit
atexit.register(savehist)
def runcode(self, code, retry=True):
source = self.cache[:-1] source = self.cache[:-1]
self.cache = "" self.cache = ""
if source != "": if source != "":
...@@ -30,50 +62,53 @@ class RosShell(InteractiveConsole): ...@@ -30,50 +62,53 @@ class RosShell(InteractiveConsole):
if not self.client: if not self.client:
print("Connection to remote server lost. Reconnecting...") print("Connection to remote server lost. Reconnecting...")
self.client = rospy.ServiceProxy( self.client = rospy.ServiceProxy(
'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True) "run_command", dynamic_graph_bridge_msgs.srv.RunCommand, True
)
if retry: if retry:
print("Retrying previous command...") print("Retrying previous command...")
self.cache = source self.cache = source
return self.runcode(code, False) return self.runcode(code, False)
response = self.client(str(source)) response = self.client(str(source))
if response.standardoutput != "": if response.standardoutput != "":
print response.standardoutput[:-1] print(response.standardoutput[:-1])
if response.standarderror != "": if response.standarderror != "":
print response.standarderror[:-1] print(response.standarderror[:-1])
elif response.result != "None": elif response.result != "None":
print response.result print(response.result)
except rospy.ServiceException, e: except rospy.ServiceException:
print("Connection to remote server lost. Reconnecting...") print("Connection to remote server lost. Reconnecting...")
self.client = rospy.ServiceProxy( self.client = rospy.ServiceProxy(
'run_command', dynamic_graph_bridge_msgs.srv.RunCommand, True) "run_command", dynamic_graph_bridge_msgs.srv.RunCommand, True
)
if retry: if retry:
print("Retrying previous command...") print("Retrying previous command...")
self.cache = source self.cache = source
self.runcode(code, False) self.runcode(code, False)
def runsource(self, source, filename = '<input>', symbol = 'single'): def runsource(self, source, filename="<input>", symbol="single"):
try: try:
c = code.compile_command(source, filename, symbol) c = code.compile_command(source, filename, symbol)
if c: if c:
return self.runcode(c) return self.runcode(c)
else: else:
return True return True
except SyntaxError, OverflowError: except (SyntaxError, OverflowError):
self.showsyntaxerror() self.showsyntaxerror()
self.cache = "" self.cache = ""
return False return False
def push(self,line): def push(self, line):
self.cache += line + "\n" self.cache += line + "\n"
return InteractiveConsole.push(self,line) return InteractiveConsole.push(self, line)
if __name__ == '__main__': if __name__ == "__main__":
import optparse import optparse
import os.path import os.path
rospy.init_node('run_command', argv=sys.argv)
rospy.init_node("run_command", argv=sys.argv)
sys.argv = rospy.myargv(argv=None) sys.argv = rospy.myargv(argv=None)
parser = optparse.OptionParser( parser = optparse.OptionParser(usage="\n\t%prog [options]")
usage='\n\t%prog [options]')
(options, args) = parser.parse_args(sys.argv[1:]) (options, args) = parser.parse_args(sys.argv[1:])
sh = RosShell() sh = RosShell()
...@@ -88,6 +123,6 @@ if __name__ == '__main__': ...@@ -88,6 +123,6 @@ if __name__ == '__main__':
if not response: if not response:
print("Error while file parsing ") print("Error while file parsing ")
else: else:
print("Provided file does not exist: %s"%(infile)) print("Provided file does not exist: %s" % (infile))
else: else:
sh.interact("Interacting with remote server.") sh.interact("Interacting with remote server.")
...@@ -6,6 +6,8 @@ ...@@ -6,6 +6,8 @@
# through dynamic_graph_bridge. # through dynamic_graph_bridge.
# #
import logging
import rospy import rospy
import tf import tf
...@@ -13,15 +15,15 @@ import geometry_msgs.msg ...@@ -13,15 +15,15 @@ import geometry_msgs.msg
def main(): def main():
rospy.init_node('tf_publisher', anonymous=True) rospy.init_node("tf_publisher", anonymous=True)
frame = rospy.get_param('~frame', '') frame = rospy.get_param("~frame", "")
childFrame = rospy.get_param('~child_frame', '') childFrame = rospy.get_param("~child_frame", "")
topic = rospy.get_param('~topic', '') topic = rospy.get_param("~topic", "")
rateSeconds = rospy.get_param('~rate', 5) rateSeconds = rospy.get_param("~rate", 5)
if not frame or not childFrame or not topic: if not frame or not childFrame or not topic:
logpy.error("frame, childFrame and topic are required parameters") logging.error("frame, childFrame and topic are required parameters")
return return
rate = rospy.Rate(rateSeconds) rate = rospy.Rate(rateSeconds)
...@@ -35,11 +37,10 @@ def main(): ...@@ -35,11 +37,10 @@ def main():
ok = False ok = False
while not rospy.is_shutdown() and not ok: while not rospy.is_shutdown() and not ok:
try: try:
tl.waitForTransform(childFrame, frame, tl.waitForTransform(childFrame, frame, rospy.Time(), rospy.Duration(0.1))
rospy.Time(), rospy.Duration(0.1))
ok = True ok = True
except tf.Exception, e: except tf.Exception:
rospy.logwarn("waiting for tf transform") logging.warning("waiting for tf transform")
ok = False ok = False
while not rospy.is_shutdown(): while not rospy.is_shutdown():
...@@ -60,4 +61,5 @@ def main(): ...@@ -60,4 +61,5 @@ def main():
pub.publish(transform) pub.publish(transform)
rate.sleep() rate.sleep()
main() main()