Skip to content
Snippets Groups Projects
Commit fe886ac1 authored by Maximilien Naveau's avatar Maximilien Naveau Committed by Olivier Stasse
Browse files

remove ros1 and the ros2 subfolder. Set it to ros2

parent 6b8de80e
No related branches found
No related tags found
No related merge requests found
Showing
with 96 additions and 650 deletions
name: Ubuntu18.04, ROS1 Continuous Integration
on:
push:
branches:
- master
- devel
- mnaveau/ubuntu20.04_ros1_ros2
pull_request:
branches:
- master
- devel
jobs:
build:
runs-on: ubuntu-18.04
steps:
#
# Setup the machines and build environment
#
- name: Install ROS.
id: ros_install
uses: ros-tooling/setup-ros@v0.2
with:
required-ros-distributions: melodic
#
# Checkout the current branch
#
- uses: actions/checkout@v2
#
# Clone the dependencies in the ROS workspace
#
- name: Clone dependencies in the current workspace.
shell: bash
run: |
mkdir -p /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src
cd /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src
git clone --recursive https://github.com/stack-of-tasks/dynamic_graph_bridge_msgs.git
#
# Build and test the repo
#
- uses: ros-tooling/action-ros-ci@v0.2
with:
package-name: dynamic_graph_bridge
target-ros1-distro: melodic
...@@ -34,14 +34,19 @@ jobs: ...@@ -34,14 +34,19 @@ jobs:
- name: Clone dependencies in the current workspace. - name: Clone dependencies in the current workspace.
shell: bash shell: bash
run: | run: |
mkdir -p /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src ws_path = /home/runner/work/dynamic_graph_bridge/colcon_workspace
cd /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src mkdir -p $ws_path/src
git clone --recursive https://github.com/stack-of-tasks/dynamic_graph_bridge_msgs.git cd $ws_path/src
git clone -b devel --single-branch --recursive https://github.com/stack-of-tasks/dynamic_graph_bridge_msgs.git
#
# Build dep and checkout from source.
#
- name: Build packages.
ln -s /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge .
colcon build
# #
# Build and test the repo # Test the checkout package
# #
- uses: ros-tooling/action-ros-ci@v0.2 colcon test --packages-select dynamic_graph_bridge --event-handlers console_direct+ --return-code-on-test-failure
with:
package-name: dynamic_graph_bridge
target-ros2-distro: foxy
name: Ubuntu20.04, ROS1 Continuous Integration
on:
push:
branches:
- master
- devel
- mnaveau/ubuntu20.04_ros1_ros2
pull_request:
branches:
- master
- devel
jobs:
build:
runs-on: ubuntu-20.04
steps:
#
# Setup the machines and build environment
#
- name: Install ROS.
uses: ros-tooling/setup-ros@v0.2
with:
required-ros-distributions: noetic
#
# Checkout the current branch
#
- uses: actions/checkout@v2
#
# Clone the dependencies in the ROS workspace
#
- name: Clone dependencies in the current workspace.
shell: bash
run: |
mkdir -p /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src
cd /home/runner/work/dynamic_graph_bridge/dynamic_graph_bridge/ros_ws/src
git clone --recursive https://github.com/stack-of-tasks/dynamic_graph_bridge_msgs.git
#
# Build and test the repo
#
- uses: ros-tooling/action-ros-ci@v0.2
with:
package-name: dynamic_graph_bridge
target-ros1-distro: noetic
...@@ -3,45 +3,85 @@ ...@@ -3,45 +3,85 @@
# Author: Florent Lamiraux, Nirmal Giftsun, Guilhem Saurel # Author: Florent Lamiraux, Nirmal Giftsun, Guilhem Saurel
# #
CMAKE_MINIMUM_REQUIRED(VERSION 3.1) cmake_minimum_required(VERSION 3.1)
# Project properties # Project properties
SET(PROJECT_ORG stack-of-tasks) set(PROJECT_ORG stack-of-tasks)
SET(PROJECT_NAME dynamic_graph_bridge) set(PROJECT_NAME dynamic_graph_bridge)
SET(PROJECT_DESCRIPTION "Dynamic graph bridge library") set(PROJECT_DESCRIPTION "Dynamic graph bridge library")
SET(PROJECT_URL "https://github.com/${PROJECT_ORG}/${PROJECT_NAME}") set(PROJECT_URL "https://github.com/${PROJECT_ORG}/${PROJECT_NAME}")
# Project options # Project options
OPTION(BUILD_PYTHON_INTERFACE "Build the python bindings" ON) option(BUILD_PYTHON_INTERFACE "Build the python bindings" ON)
# Project configuration # Project configuration
SET(PROJECT_USE_CMAKE_EXPORT TRUE) set(PROJECT_USE_CMAKE_EXPORT TRUE)
SET(CUSTOM_HEADER_DIR ${PROJECT_NAME}) set(CUSTOM_HEADER_DIR ${PROJECT_NAME})
set(CXX_DISABLE_WERROR FALSE) set(CXX_DISABLE_WERROR FALSE)
SET(DOXYGEN_USE_MATHJAX YES) set(DOXYGEN_USE_MATHJAX YES)
SET(CATKIN_ENABLE_TESTING OFF) set(CATKIN_ENABLE_TESTING OFF)
# JRL-cmakemodule setup # JRL-cmakemodule setup
INCLUDE(cmake/base.cmake) include(cmake/base.cmake)
INCLUDE(cmake/boost.cmake) include(cmake/boost.cmake)
INCLUDE(cmake/python.cmake) include(cmake/python.cmake)
INCLUDE(cmake/ros.cmake) include(cmake/ros.cmake)
# Project definition # Project definition
COMPUTE_PROJECT_ARGS(PROJECT_ARGS LANGUAGES CXX) compute_project_args(PROJECT_ARGS LANGUAGES CXX)
PROJECT(${PROJECT_NAME} ${PROJECT_ARGS}) project(${PROJECT_NAME} ${PROJECT_ARGS})
if(DEFINED ENV{ROS_VERSION} ) if(NOT CMAKE_CXX_STANDARD)
if ($ENV{ROS_VERSION} EQUAL 2) # if ROS2 set(CMAKE_CXX_STANDARD 14)
add_subdirectory(ros2)
#ROS 2 packaging
ament_package()
else()
add_subdirectory(ros1)
endif()
else()
message(FATAL_ERROR "No ROS version found.")
endif() endif()
cmake_policy(SET CMP0057 NEW)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(ament_cmake_core REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rcutils REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
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(BUILD_PYTHON_INTERFACE)
findpython()
search_for_boost_python()
string(REGEX REPLACE "-" "_" PY_NAME ${PROJECT_NAME})
add_project_dependency(dynamic-graph-python 4.0.0 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()
endif(BUILD_PYTHON_INTERFACE)
add_subdirectory(src)
add_subdirectory(tests)
# install ros executables
install(
PROGRAMS scripts/remote_python_client.py
RENAME remote_python_client
DESTINATION lib/${PROJECT_NAME})
install(
PROGRAMS scripts/remote_python_client.py
RENAME run_command
DESTINATION lib/${PROJECT_NAME})
# we also need to install the header files
install(DIRECTORY include/ DESTINATION include)
# Install package information # Install package information
install(FILES manifest.xml package.xml DESTINATION share/${PROJECT_NAME}) install(FILES package.xml DESTINATION share/${PROJECT_NAME})
\ No newline at end of file
#ROS 2 packaging
ament_package()
\ No newline at end of file
<package>
<description brief="Dynamic graph ROS bridge">
ROS bindings for dynamic graph.
</description>
<author>Thomas Moulard</author>
<license>BSD</license>
<review status="unreviewed" notes=""/>
<url>http://ros.org/wiki/dynamic_graph_bridge</url>
<export>
<cpp
cflags="-I${prefix}/include"
lflags="-L${prefix}/lib -lros_bridge -lros_interpreter -Wl,-rpath,${prefix}/lib"
/>
<rosdoc config="rosdoc.yaml" />
</export>
<rosdep name="boost"/>
<!-- Disable non-standard dependencies for now
<rosdep name="jrl-mal"/>
<rosdep name="dynamic-graph"/>
<rosdep name="sot-core"/>
<rosdep name="sot-dynamic"/>
-->
<depend package="std_msgs"/>
<depend package="std_srvs"/>
<depend package="roscpp"/>
<depend package="geometry_msgs"/>
<depend package="sensor_msgs"/>
<depend package="tf"/>
<depend package="realtime_tools"/>
<depend package="dynamic_graph_bridge_msgs"/>
</package>
...@@ -10,58 +10,25 @@ ...@@ -10,58 +10,25 @@
<license>LGPL</license> <license>LGPL</license>
<url>http://ros.org/wiki/dynamic_graph_bridge</url> <url>http://ros.org/wiki/dynamic_graph_bridge</url>
<!-- ROS1 dependencies -->
<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<build_depend condition="$ROS_VERSION == 1">std_msgs</build_depend>
<build_depend condition="$ROS_VERSION == 1">std_srvs</build_depend>
<build_depend condition="$ROS_VERSION == 1">roscpp</build_depend>
<build_depend condition="$ROS_VERSION == 1">geometry_msgs</build_depend>
<build_depend condition="$ROS_VERSION == 1">sensor_msgs</build_depend>
<build_depend condition="$ROS_VERSION == 1">tf2_ros</build_depend>
<build_depend condition="$ROS_VERSION == 1">realtime_tools</build_depend>
<build_depend condition="$ROS_VERSION == 1">message_generation</build_depend>
<build_depend condition="$ROS_VERSION == 1">message_runtime</build_depend>
<build_depend condition="$ROS_VERSION == 1">dynamic-graph</build_depend>
<build_depend condition="$ROS_VERSION == 1">dynamic-graph-python</build_depend>
<build_depend condition="$ROS_VERSION == 1">sot-core</build_depend>
<build_depend condition="$ROS_VERSION == 1">sot-dynamic-pinocchio</build_depend>
<build_depend condition="$ROS_VERSION == 1">dynamic_graph_bridge_msgs</build_depend>
<exec_depend condition="$ROS_VERSION == 1">std_msgs</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">std_srvs</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">roscpp</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">geometry_msgs</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">sensor_msgs</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">tf2_ros</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">realtime_tools</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">message_generation</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">message_runtime</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">dynamic-graph</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">dynamic-graph-python</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">sot-core</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">sot-dynamic-pinocchio</exec_depend>
<exec_depend condition="$ROS_VERSION == 1">dynamic_graph_bridge_msgs</exec_depend>
<!-- ROS2 dependencies --> <!-- ROS2 dependencies -->
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend> <buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 2">ament_index_cpp</buildtool_depend> <buildtool_depend>ament_index_cpp</buildtool_depend>
<depend condition="$ROS_VERSION == 2"> rclcpp </depend> <depend > rclcpp </depend>
<exec_depend condition="$ROS_VERSION == 2"> rclpy </exec_depend> <exec_depend > rclpy </exec_depend>
<depend condition="$ROS_VERSION == 2"> rcutils </depend> <depend > rcutils </depend>
<depend condition="$ROS_VERSION == 2"> std_msgs </depend> <depend > std_msgs </depend>
<depend condition="$ROS_VERSION == 2"> std_srvs </depend> <depend > std_srvs </depend>
<depend condition="$ROS_VERSION == 2"> geometry_msgs </depend> <depend > geometry_msgs </depend>
<depend condition="$ROS_VERSION == 2"> sensor_msgs </depend> <depend > sensor_msgs </depend>
<depend condition="$ROS_VERSION == 2"> tf2_ros </depend> <depend > tf2_ros </depend>
<depend condition="$ROS_VERSION == 2"> boost </depend> <depend > boost </depend>
<depend condition="$ROS_VERSION == 2"> dynamic_graph_bridge_msgs </depend> <depend > dynamic_graph_bridge_msgs </depend>
<depend condition="$ROS_VERSION == 2"> sot-core </depend> <depend > sot-core </depend>
<export> <export>
<rosdoc config="rosdoc.yaml" /> <rosdoc config="rosdoc.yaml" />
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type> <build_type>ament_cmake</build_type>
</export> </export>
<test_depend condition="$ROS_VERSION == 2">rclpy</test_depend> <test_depend>rclpy</test_depend>
</package> </package>
# Copyright (C) 2008-2020 LAAS-CNRS, JRL AIST-CNRS.
#
# Author: Florent Lamiraux, Nirmal Giftsun, Guilhem Saurel, Maxmilien Naveau
#
# Project dependencies
SET(CATKIN_REQUIRED_COMPONENTS roscpp std_msgs message_generation std_srvs geometry_msgs sensor_msgs tf2_ros
realtime_tools)
ADD_PROJECT_DEPENDENCY(Boost REQUIRED COMPONENTS program_options)
ADD_PROJECT_DEPENDENCY(dynamic_graph_bridge_msgs 0.3.0 REQUIRED)
IF(BUILD_PYTHON_INTERFACE)
FINDPYTHON()
SEARCH_FOR_BOOST_PYTHON()
STRING(REGEX REPLACE "-" "_" PY_NAME ${PROJECT_NAME})
ADD_PROJECT_DEPENDENCY(dynamic-graph-python 4.0.0 REQUIRED)
SET(CATKIN_REQUIRED_COMPONENTS ${CATKIN_REQUIRED_COMPONENTS} rospy)
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()
ENDIF(BUILD_PYTHON_INTERFACE)
find_package(catkin REQUIRED COMPONENTS ${CATKIN_REQUIRED_COMPONENTS})
ADD_PROJECT_DEPENDENCY(sot-core REQUIRED)
# 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>
PRIVATE ${PROJECT_SOURCE_DIR}/ros1/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(tests)
#install ros executables
install(PROGRAMS
scripts/robot_pose_publisher
scripts/run_command
scripts/tf_publisher
DESTINATION share/${PROJECT_NAME}
)
# we also need to install the header files
install(DIRECTORY include/ DESTINATION include)
/*
* 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/python/fwd.hh>
namespace dynamicgraph {
// classes defined in sot-core
class Interpreter;
typedef shared_ptr<Interpreter> InterpreterPtr_t;
}// namespace dynamicgraph
#endif // DYNAMIC_GRAPH_PYTHON_FWD_HH
#ifndef ROS_INIT_HH
#define ROS_INIT_HH
#include <ros/ros.h>
namespace dynamicgraph {
ros::NodeHandle& rosInit(bool createAsyncSpinner = false, bool createMultiThreadSpinner = true);
/// \brief Return spinner or throw an exception if spinner
/// creation has been disabled at startup.
ros::AsyncSpinner& spinner();
/// \brief Return multi threaded spinner or throw an exception if spinner
/// creation has been disabled at startup.
ros::MultiThreadedSpinner& mtSpinner();
} // end of namespace dynamicgraph.
#endif //! ROS_INIT_HH
#ifndef DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH
#define DYNAMIC_GRAPH_BRIDGE_INTERPRETER_HH
#pragma GCC diagnostic push
#pragma GCC system_header
#include <ros/ros.h>
#pragma GCC diagnostic pop
#include <dynamic_graph_bridge/fwd.hh>
#include <dynamic_graph_bridge_msgs/RunCommand.h>
#include <dynamic_graph_bridge_msgs/RunPythonFile.h>
#include <dynamic-graph/python/interpreter.hh>
namespace dynamicgraph {
/// \brief This class wraps the implementation of the runCommand
/// service.
///
/// This takes as input a ROS node handle and do not handle the
/// callback so that the service behavior can be controlled from
/// the outside.
class Interpreter {
public:
typedef boost::function<bool(dynamic_graph_bridge_msgs::RunCommand::Request&,
dynamic_graph_bridge_msgs::RunCommand::Response&)>
runCommandCallback_t;
typedef boost::function<bool(dynamic_graph_bridge_msgs::RunPythonFile::Request&,
dynamic_graph_bridge_msgs::RunPythonFile::Response&)>
runPythonFileCallback_t;
explicit Interpreter(ros::NodeHandle& nodeHandle);
/// \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, std::string& out, std::string& err);
/// \brief Method to parse python scripts.
/// \param Input file name to parse.
void runPythonFile(std::string ifilename);
/// Initialize service run_command
void startRosService();
protected:
/// \brief Run a Python command and return result, stderr and stdout.
bool runCommandCallback(dynamic_graph_bridge_msgs::RunCommand::Request& req,
dynamic_graph_bridge_msgs::RunCommand::Response& res);
/// \brief Run a Python file.
bool runPythonFileCallback(dynamic_graph_bridge_msgs::RunPythonFile::Request& req,
dynamic_graph_bridge_msgs::RunPythonFile::Response& res);
private:
python::Interpreter interpreter_;
ros::NodeHandle& nodeHandle_;
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 2016,
* Olivier Stasse,
*
* CNRS
*
*/
/* -------------------------------------------------------------------------- */
/* --- INCLUDES ------------------------------------------------------------- */
/* -------------------------------------------------------------------------- */
#ifndef _SOT_LOADER_HH_
#define _SOT_LOADER_HH_
// System includes
#include <cassert>
// STL includes
#include <map>
// Pinocchio includes
#include <pinocchio/fwd.hpp>
// Boost includes
#include <boost/program_options.hpp>
#include <boost/foreach.hpp>
#include <boost/format.hpp>
#include <boost/thread/thread.hpp>
// ROS includes
#include "ros/ros.h"
#include "std_srvs/Empty.h"
#include <sensor_msgs/JointState.h>
#include <tf2_ros/transform_broadcaster.h>
// Sot Framework includes
#include <sot/core/debug.hh>
#include <sot/core/abstract-sot-external-interface.hh>
// Dynamic-graph-bridge includes.
#include <dynamic_graph_bridge/sot_loader_basic.hh>
namespace po = boost::program_options;
namespace dgs = dynamicgraph::sot;
class SotLoader : public SotLoaderBasic {
protected:
/// Map of sensor readings
std::map<std::string, dgs::SensorValues> sensorsIn_;
/// Map of control values
std::map<std::string, dgs::ControlValues> controlValues_;
/// Angular values read by encoders
std::vector<double> angleEncoder_;
/// Angular values sent to motors
std::vector<double> angleControl_;
/// Forces read by force sensors
std::vector<double> forces_;
/// Torques
std::vector<double> torques_;
/// Attitude of the robot computed by extended Kalman filter.
std::vector<double> baseAtt_;
/// Accelerations read by Accelerometers
std::vector<double> accelerometer_;
/// Angular velocity read by gyrometers
std::vector<double> gyrometer_;
/// URDF string description of the robot.
std::string robot_desc_string_;
/// The thread running dynamic graph
boost::thread thread_;
// \brief Start control loop
virtual void startControlLoop();
// Robot Pose Publisher
tf2_ros::TransformBroadcaster freeFlyerPublisher_;
geometry_msgs::TransformStamped freeFlyerPose_;
public:
SotLoader();
~SotLoader();
// \brief Create a thread for ROS and start the control loop.
void initializeRosNode(int argc, char *argv[]);
// \brief Compute one iteration of control.
// Basically calls fillSensors, the SoT and the readControl.
void oneIteration();
// \brief Fill the sensors value for the SoT.
void fillSensors(std::map<std::string, dgs::SensorValues> &sensorsIn);
// \brief Read the control computed by the SoT framework.
void readControl(std::map<std::string, dgs::ControlValues> &controlValues);
// \brief Prepare the SoT framework.
void setup();
};
#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/program_options.hpp>
#include <boost/foreach.hpp>
#include <boost/format.hpp>
// ROS includes
#include "ros/ros.h"
#include "std_srvs/Empty.h"
#include <sensor_msgs/JointState.h>
// Sot Framework includes
#include <sot/core/debug.hh>
#include <sot/core/abstract-sot-external-interface.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_ */
#!/usr/bin/env python
#
# Listens to TransformStamped messages and publish them to tf
#
import rospy
import tf
import sensor_msgs.msg
frame = ''
childFrame = ''
#DEPRECATED. Robot Pose is already being published
def pose_broadcaster(msg):
translation = msg.position[0:3];
rotation = tf.transformations.quaternion_from_euler(msg.position[3], msg.position[4], msg.position[5])
tfbr = tf.TransformBroadcaster()
tfbr.sendTransform(translation, rotation,
rospy.Time.now(), childFrame, frame)
if __name__ == '__main__':
rospy.init_node('robot_pose_publisher', anonymous=True)
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.spin()
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment