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
Showing
with 760 additions and 997 deletions
[tool.black]
exclude = "cmake"
#!/usr/bin/env python
#
# Listens to TransformStamped messages and publish them to tf
#
import rospy
import tf
import sensor_msgs.msg
frame = ""
childFrame = ""
def pose_broadcaster(msg):
# DEPRECATED. Robot Pose is already being published
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()
#!/usr/bin/env python #!/usr/bin/env python
import roslib; roslib.load_manifest('dynamic_graph_bridge')
import rospy import rospy
import dynamic_graph_bridge.srv import dynamic_graph # noqa: F401
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.srv.RunCommand, True) "run_command", dynamic_graph_bridge_msgs.srv.RunCommand, True
)
rospy.wait_for_service("run_script")
self.scriptClient = rospy.ServiceProxy(
"run_script", dynamic_graph_bridge_msgs.srv.RunPythonFile, 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
def runcode(self, code, retry = True): 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 != "":
...@@ -29,65 +62,67 @@ class RosShell(InteractiveConsole): ...@@ -29,65 +62,67 @@ 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.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.stdout != "": if response.standardoutput != "":
print response.stdout[:-1] print(response.standardoutput[:-1])
if response.stderr != "": if response.standarderror != "":
print response.stderr[:-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.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
manifest = roslib.manifest.load_manifest('dynamic_graph_bridge') import os.path
parser = optparse.OptionParser(
usage='\n\t%prog [options]', rospy.init_node("run_command", argv=sys.argv)
version='%%prog %s' % manifest.version) sys.argv = rospy.myargv(argv=None)
parser = optparse.OptionParser(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()
if args[:]: if args[:]:
infile = args[0] infile = args[0]
source = open(infile).read() if os.path.isfile(infile):
if not sh.client: if not sh.client:
print("Connection to remote server has been lost.") print("Connection to remote server has been lost.")
sys.exit(1) sys.exit(1)
response = sh.client(str(source)) response = sh.scriptClient(os.path.abspath(infile))
if response.stdout != "": if not response:
print response.stdout[:-1] print("Error while file parsing ")
if response.stderr != "": else:
print response.stderr[:-1] print("Provided file does not exist: %s" % (infile))
elif response.result != "None":
print response.result
else: else:
sh.interact("Interacting with remote server.") sh.interact("Interacting with remote server.")
...@@ -6,8 +6,8 @@ ...@@ -6,8 +6,8 @@
# through dynamic_graph_bridge. # through dynamic_graph_bridge.
# #
import roslib import logging
roslib.load_manifest('dynamic_graph_bridge')
import rospy import rospy
import tf import tf
...@@ -15,15 +15,15 @@ import geometry_msgs.msg ...@@ -15,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)
...@@ -37,11 +37,10 @@ def main(): ...@@ -37,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():
...@@ -62,4 +61,5 @@ def main(): ...@@ -62,4 +61,5 @@ def main():
pub.publish(transform) pub.publish(transform)
rate.sleep() rate.sleep()
main() main()
[flake8]
exclude = cmake
max-line-length = 88
extend-ignore = E203
PYTHON_INSTALL("dynamic_graph/ros" "__init__.py" "${PYTHON_SITELIB}") set(plugins ros_publish ros_subscribe ros_queued_subscribe ros_tf_listener
PYTHON_INSTALL("dynamic_graph/ros" "ros.py" "${PYTHON_SITELIB}") ros_time)
\ No newline at end of file
foreach(plugin ${plugins})
get_filename_component(LIBRARY_NAME ${plugin} NAME)
add_library(${LIBRARY_NAME} SHARED ${plugin}.cpp ${plugin}.hh)
if(SUFFIX_SO_VERSION)
set_target_properties(${LIBRARY_NAME} PROPERTIES SOVERSION
${PROJECT_VERSION})
endif(SUFFIX_SO_VERSION)
target_link_libraries(${LIBRARY_NAME} ${${LIBRARY_NAME}_deps}
${catkin_LIBRARIES} ros_bridge)
if(NOT INSTALL_PYTHON_INTERFACE_ONLY)
install(
TARGETS ${LIBRARY_NAME}
EXPORT ${TARGETS_EXPORT_NAME}
DESTINATION ${DYNAMIC_GRAPH_PLUGINDIR})
endif(NOT INSTALL_PYTHON_INTERFACE_ONLY)
if(BUILD_PYTHON_INTERFACE)
string(REPLACE - _ PYTHON_LIBRARY_NAME ${LIBRARY_NAME})
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python-module-py.cc")
dynamic_graph_python_module(
"ros/${PYTHON_LIBRARY_NAME}" ${LIBRARY_NAME}
${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap SOURCE_PYTHON_MODULE
"${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python-module-py.cc")
elseif(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python.hh")
dynamic_graph_python_module(
"ros/${PYTHON_LIBRARY_NAME}" ${LIBRARY_NAME}
${PROJECT_NAME}-${PYTHON_LIBRARY_NAME}-wrap MODULE_HEADER
"${CMAKE_CURRENT_SOURCE_DIR}/${plugin}-python.hh")
endif()
endif(BUILD_PYTHON_INTERFACE)
endforeach(plugin)
target_link_libraries(ros_publish ros_bridge)
if(BUILD_PYTHON_INTERFACE)
python_install_on_site("dynamic_graph/ros" "__init__.py")
python_install_on_site("dynamic_graph/ros" "ros.py")
python_install_on_site("dynamic_graph/ros" "dgcompleter.py")
# ros_interperter library.
add_library(ros_interpreter ros_interpreter.cpp)
target_link_libraries(ros_interpreter ros_bridge ${catkin_LIBRARIES}
dynamic-graph-python::dynamic-graph-python)
install(
TARGETS ros_interpreter
EXPORT ${TARGETS_EXPORT_NAME}
DESTINATION lib)
endif(BUILD_PYTHON_INTERFACE)
# Stand alone embedded intepreter with a robot controller.
add_executable(geometric_simu geometric_simu.cpp sot_loader.cpp
sot_loader_basic.cpp)
target_link_libraries(geometric_simu Boost::program_options ${CMAKE_DL_LIBS}
${catkin_LIBRARIES} ros_bridge)
install(TARGETS geometric_simu DESTINATION lib/${PROJECT_NAME})
# Sot loader library
add_library(sot_loader sot_loader.cpp sot_loader_basic.cpp)
target_link_libraries(sot_loader Boost::program_options ${catkin_LIBRARIES}
ros_bridge)
install(
TARGETS sot_loader
EXPORT ${TARGETS_EXPORT_NAME}
DESTINATION lib)
#ifndef DYNAMIC_GRAPH_ROS_CONVERTER_HH #ifndef DYNAMIC_GRAPH_ROS_CONVERTER_HH
# define DYNAMIC_GRAPH_ROS_CONVERTER_HH #define DYNAMIC_GRAPH_ROS_CONVERTER_HH
# include <stdexcept> #include <ros/time.h>
# include "sot_to_ros.hh" #include <std_msgs/Header.h>
# include <boost/static_assert.hpp> #include <boost/date_time/date.hpp>
# include <boost/date_time/date.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
# include <boost/date_time/posix_time/posix_time.hpp> #include <boost/static_assert.hpp>
#include <stdexcept>
# include <ros/time.h>
# include <std_msgs/Header.h> #include "sot_to_ros.hh"
# include <LinearMath/btMatrix3x3.h> #define SOT_TO_ROS_IMPL(T) \
# include <LinearMath/btQuaternion.h> template <> \
inline void converter(SotToRos<T>::ros_t& dst, \
# define SOT_TO_ROS_IMPL(T) \ const SotToRos<T>::sot_t& src)
template <> \
inline void \ #define ROS_TO_SOT_IMPL(T) \
converter (SotToRos<T>::ros_t& dst, const SotToRos<T>::sot_t& src) template <> \
inline void converter(SotToRos<T>::sot_t& dst, \
# define ROS_TO_SOT_IMPL(T) \ const SotToRos<T>::ros_t& src)
template <> \
inline void \ namespace dynamicgraph {
converter (SotToRos<T>::sot_t& dst, const SotToRos<T>::ros_t& src) inline void makeHeader(std_msgs::Header& header) {
header.seq = 0;
namespace dynamicgraph header.stamp = ros::Time::now();
{ header.frame_id = "/dynamic_graph/world";
inline }
void
makeHeader(std_msgs::Header& header) /// \brief Handle ROS <-> dynamic-graph conversion.
{ ///
header.seq = 0; /// Implements all ROS/dynamic-graph conversions required by the
header.stamp = ros::Time::now (); /// bridge.
header.frame_id = "/dynamic_graph/world"; ///
/// Relies on the SotToRos type trait to make sure valid pair of
/// types are used.
template <typename D, typename S>
void converter(D& dst, const S& src);
// Boolean
SOT_TO_ROS_IMPL(bool) { dst.data = src; }
ROS_TO_SOT_IMPL(bool) { dst = src.data; }
// Double
SOT_TO_ROS_IMPL(double) { dst.data = src; }
ROS_TO_SOT_IMPL(double) { dst = src.data; }
// Int
SOT_TO_ROS_IMPL(int) { dst.data = src; }
ROS_TO_SOT_IMPL(int) { dst = src.data; }
// Unsigned
SOT_TO_ROS_IMPL(unsigned int) { dst.data = src; }
ROS_TO_SOT_IMPL(unsigned int) { dst = src.data; }
// String
SOT_TO_ROS_IMPL(std::string) { dst.data = src; }
ROS_TO_SOT_IMPL(std::string) { dst = src.data; }
// Vector
SOT_TO_ROS_IMPL(Vector) {
dst.data.resize(src.size());
for (int i = 0; i < src.size(); ++i) dst.data[i] = src(i);
}
ROS_TO_SOT_IMPL(Vector) {
dst.resize(src.data.size());
for (unsigned int i = 0; i < src.data.size(); ++i) dst(i) = src.data[i];
}
// Vector3
SOT_TO_ROS_IMPL(specific::Vector3) {
if (src.size() > 0) {
dst.x = src(0);
if (src.size() > 1) {
dst.y = src(1);
if (src.size() > 2) dst.z = src(2);
}
} }
}
/// \brief Handle ROS <-> dynamic-graph conversion.
/// ROS_TO_SOT_IMPL(specific::Vector3) {
/// Implements all ROS/dynamic-graph conversions required by the dst.resize(3);
/// bridge. dst(0) = src.x;
/// dst(1) = src.y;
///Relies on the SotToRos type trait to make sure valid pair of dst(2) = src.z;
/// types are used. }
template <typename D, typename S>
void converter (D& dst, const S& src); // Matrix
SOT_TO_ROS_IMPL(Matrix) {
// Double // TODO: Confirm Ros Matrix Storage order. It changes the RosMatrix to
SOT_TO_ROS_IMPL(double) // ColMajor.
{ dst.width = (unsigned int)src.rows();
dst.data = src; dst.data.resize(src.cols() * src.rows());
} for (int i = 0; i < src.cols() * src.rows(); ++i) dst.data[i] = src.data()[i];
}
ROS_TO_SOT_IMPL(double)
{ ROS_TO_SOT_IMPL(Matrix) {
dst = src.data; dst.resize(src.width,
} (unsigned int)src.data.size() / (unsigned int)src.width);
for (unsigned i = 0; i < src.data.size(); ++i) dst.data()[i] = src.data[i];
// Unsigned }
SOT_TO_ROS_IMPL(unsigned int)
{ // Homogeneous matrix.
dst.data = src; SOT_TO_ROS_IMPL(sot::MatrixHomogeneous) {
} sot::VectorQuaternion q(src.linear());
dst.translation.x = src.translation()(0);
ROS_TO_SOT_IMPL(unsigned int) dst.translation.y = src.translation()(1);
{ dst.translation.z = src.translation()(2);
dst = src.data;
} dst.rotation.x = q.x();
dst.rotation.y = q.y();
// Vector dst.rotation.z = q.z();
SOT_TO_ROS_IMPL(ml::Vector) dst.rotation.w = q.w();
{ }
dst.data.resize (src.size ());
for (unsigned i = 0; i < src.size (); ++i) ROS_TO_SOT_IMPL(sot::MatrixHomogeneous) {
dst.data[i] = src.elementAt (i); sot::VectorQuaternion q(src.rotation.w, src.rotation.x, src.rotation.y,
} src.rotation.z);
dst.linear() = q.matrix();
ROS_TO_SOT_IMPL(ml::Vector)
{ // Copy the translation component.
dst.resize (src.data.size ()); dst.translation()(0) = src.translation.x;
for (unsigned i = 0; i < src.data.size (); ++i) dst.translation()(1) = src.translation.y;
dst.elementAt (i) = src.data[i]; dst.translation()(2) = src.translation.z;
} }
// Vector3 // Twist.
SOT_TO_ROS_IMPL(specific::Vector3) SOT_TO_ROS_IMPL(specific::Twist) {
{ if (src.size() != 6)
if (src.size () > 0) throw std::runtime_error("failed to convert invalid twist");
{ dst.linear.x = src(0);
dst.x = src.elementAt (0); dst.linear.y = src(1);
if (src.size () > 1) dst.linear.z = src(2);
{ dst.angular.x = src(3);
dst.y = src.elementAt (1); dst.angular.y = src(4);
if (src.size () > 2) dst.angular.z = src(5);
dst.z = src.elementAt (2); }
}
} ROS_TO_SOT_IMPL(specific::Twist) {
} dst.resize(6);
dst(0) = src.linear.x;
ROS_TO_SOT_IMPL(specific::Vector3) dst(1) = src.linear.y;
{ dst(2) = src.linear.z;
dst.resize (3); dst(3) = src.angular.x;
dst.elementAt (0) = src.x; dst(4) = src.angular.y;
dst.elementAt (1) = src.y; dst(5) = src.angular.z;
dst.elementAt (2) = src.z; }
}
/// \brief This macro generates a converter for a stamped type from
// Matrix /// dynamic-graph to ROS. I.e. A data associated with its
SOT_TO_ROS_IMPL(ml::Matrix) /// timestamp.
{ #define DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(T, ATTRIBUTE, EXTRA) \
dst.width = src.nbRows (); template <> \
dst.data.resize (src.nbCols () * src.nbRows ()); inline void converter(SotToRos<std::pair<T, Vector> >::ros_t& dst, \
for (unsigned i = 0; i < src.nbCols () * src.nbRows (); ++i) const SotToRos<std::pair<T, Vector> >::sot_t& src) { \
dst.data[i] = src.elementAt (i); makeHeader(dst.header); \
} converter<SotToRos<T>::ros_t, SotToRos<T>::sot_t>(dst.ATTRIBUTE, src); \
do { \
ROS_TO_SOT_IMPL(ml::Matrix) EXTRA \
{ } while (0); \
dst.resize (src.width, src.data.size () / src.width); } \
for (unsigned i = 0; i < src.data.size (); ++i)
dst.elementAt (i) = src.data[i];
}
// Homogeneous matrix.
SOT_TO_ROS_IMPL(sot::MatrixHomogeneous)
{
btMatrix3x3 rotation;
btQuaternion quaternion;
for(unsigned i = 0; i < 3; ++i)
for(unsigned j = 0; j < 3; ++j)
rotation[i][j] = src (i, j);
rotation.getRotation (quaternion);
dst.translation.x = src (0, 3);
dst.translation.y = src (1, 3);
dst.translation.z = src (2, 3);
dst.rotation.x = quaternion.x ();
dst.rotation.y = quaternion.y ();
dst.rotation.z = quaternion.z ();
dst.rotation.w = quaternion.w ();
}
ROS_TO_SOT_IMPL(sot::MatrixHomogeneous)
{
btQuaternion quaternion
(src.rotation.x, src.rotation.y, src.rotation.z, src.rotation.w);
btMatrix3x3 rotation (quaternion);
// Copy the rotation component.
for(unsigned i = 0; i < 3; ++i)
for(unsigned j = 0; j < 3; ++j)
dst (i, j) = rotation[i][j];
// Copy the translation component.
dst(0, 3) = src.translation.x;
dst(1, 3) = src.translation.y;
dst(2, 3) = src.translation.z;
}
// Twist.
SOT_TO_ROS_IMPL(specific::Twist)
{
if (src.size () != 6)
throw std::runtime_error ("failed to convert invalid twist");
dst.linear.x = src (0);
dst.linear.y = src (1);
dst.linear.z = src (2);
dst.angular.x = src (3);
dst.angular.y = src (4);
dst.angular.z = src (5);
}
ROS_TO_SOT_IMPL(specific::Twist)
{
dst.resize (6);
dst (0) = src.linear.x;
dst (1) = src.linear.y;
dst (2) = src.linear.z;
dst (3) = src.angular.x;
dst (4) = src.angular.y;
dst (5) = src.angular.z;
}
/// \brief This macro generates a converter for a stamped type from
/// dynamic-graph to ROS. I.e. A data associated with its
/// timestamp.
# define DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(T, ATTRIBUTE, EXTRA) \
template <> \
inline void converter \
(SotToRos<std::pair<T, ml::Vector> >::ros_t& dst, \
const SotToRos<std::pair<T, ml::Vector> >::sot_t& src) \
{ \
makeHeader(dst.header); \
converter<SotToRos<T>::ros_t, SotToRos<T>::sot_t> (dst.ATTRIBUTE, src); \
do { EXTRA } while (0); \
} \
struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n
DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Vector3, vector, ;); DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Vector3, vector, ;);
DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(sot::MatrixHomogeneous, transform, DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(sot::MatrixHomogeneous, transform,
dst.child_frame_id = "";); dst.child_frame_id = "";);
DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Twist, twist, ;); DG_BRIDGE_TO_ROS_MAKE_STAMPED_IMPL(specific::Twist, twist, ;);
/// \brief This macro generates a converter for a shared pointer on
/// \brief This macro generates a converter for a shared pointer on /// a ROS type to a dynamic-graph type.
/// a ROS type to a dynamic-graph type. ///
/// /// A converter for the underlying type is required. I.e. to
/// A converter for the underlying type is required. I.e. to /// convert a shared_ptr<T> to T', a converter from T to T'
/// convert a shared_ptr<T> to T', a converter from T to T' /// is required.
/// is required. #define DG_BRIDGE_MAKE_SHPTR_IMPL(T) \
# define DG_BRIDGE_MAKE_SHPTR_IMPL(T) \ template <> \
template <> \ inline void converter( \
inline void converter \ SotToRos<T>::sot_t& dst, \
(SotToRos<T>::sot_t& dst, \ const boost::shared_ptr<SotToRos<T>::ros_t const>& src) { \
const boost::shared_ptr<SotToRos<T>::ros_t const>& src) \ converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t>(dst, *src); \
{ \ } \
converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t> (dst, *src); \
} \
struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n
DG_BRIDGE_MAKE_SHPTR_IMPL(double); DG_BRIDGE_MAKE_SHPTR_IMPL(bool);
DG_BRIDGE_MAKE_SHPTR_IMPL(unsigned int); DG_BRIDGE_MAKE_SHPTR_IMPL(double);
DG_BRIDGE_MAKE_SHPTR_IMPL(ml::Vector); DG_BRIDGE_MAKE_SHPTR_IMPL(int);
DG_BRIDGE_MAKE_SHPTR_IMPL(specific::Vector3); DG_BRIDGE_MAKE_SHPTR_IMPL(unsigned int);
DG_BRIDGE_MAKE_SHPTR_IMPL(ml::Matrix); DG_BRIDGE_MAKE_SHPTR_IMPL(std::string);
DG_BRIDGE_MAKE_SHPTR_IMPL(sot::MatrixHomogeneous); DG_BRIDGE_MAKE_SHPTR_IMPL(Vector);
DG_BRIDGE_MAKE_SHPTR_IMPL(specific::Twist); DG_BRIDGE_MAKE_SHPTR_IMPL(specific::Vector3);
DG_BRIDGE_MAKE_SHPTR_IMPL(Matrix);
/// \brief This macro generates a converter for a stamped type. DG_BRIDGE_MAKE_SHPTR_IMPL(sot::MatrixHomogeneous);
/// I.e. A data associated with its timestamp. DG_BRIDGE_MAKE_SHPTR_IMPL(specific::Twist);
///
/// FIXME: the timestamp is not yet forwarded to the dg signal. /// \brief This macro generates a converter for a stamped type.
# define DG_BRIDGE_MAKE_STAMPED_IMPL(T, ATTRIBUTE, EXTRA) \ /// I.e. A data associated with its timestamp.
template <> \ ///
inline void converter \ /// FIXME: the timestamp is not yet forwarded to the dg signal.
(SotToRos<std::pair<T, ml::Vector> >::sot_t& dst, \ #define DG_BRIDGE_MAKE_STAMPED_IMPL(T, ATTRIBUTE, EXTRA) \
const SotToRos<std::pair<T, ml::Vector> >::ros_t& src) \ template <> \
{ \ inline void converter(SotToRos<std::pair<T, Vector> >::sot_t& dst, \
converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t> (dst, src.ATTRIBUTE); \ const SotToRos<std::pair<T, Vector> >::ros_t& src) { \
do { EXTRA } while (0); \ converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t>(dst, src.ATTRIBUTE); \
} \ do { \
EXTRA \
} while (0); \
} \
struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n
DG_BRIDGE_MAKE_STAMPED_IMPL(specific::Vector3, vector, ;); DG_BRIDGE_MAKE_STAMPED_IMPL(specific::Vector3, vector, ;);
DG_BRIDGE_MAKE_STAMPED_IMPL(sot::MatrixHomogeneous, transform, ;); DG_BRIDGE_MAKE_STAMPED_IMPL(sot::MatrixHomogeneous, transform, ;);
DG_BRIDGE_MAKE_STAMPED_IMPL(specific::Twist, twist, ;); DG_BRIDGE_MAKE_STAMPED_IMPL(specific::Twist, twist, ;);
/// \brief This macro generates a converter for a shared pointer on /// \brief This macro generates a converter for a shared pointer on
/// a stamped type. I.e. A data associated with its timestamp. /// a stamped type. I.e. A data associated with its timestamp.
/// ///
/// FIXME: the timestamp is not yet forwarded to the dg signal. /// FIXME: the timestamp is not yet forwarded to the dg signal.
# define DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(T, ATTRIBUTE, EXTRA) \ #define DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(T, ATTRIBUTE, EXTRA) \
template <> \ template <> \
inline void converter \ inline void converter( \
(SotToRos<std::pair<T, ml::Vector> >::sot_t& dst, \ SotToRos<std::pair<T, Vector> >::sot_t& dst, \
const boost::shared_ptr \ const boost::shared_ptr<SotToRos<std::pair<T, Vector> >::ros_t const>& \
<SotToRos<std::pair<T, ml::Vector> >::ros_t const>& src) \ src) { \
{ \ converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t>(dst, src->ATTRIBUTE); \
converter<SotToRos<T>::sot_t, SotToRos<T>::ros_t> (dst, src->ATTRIBUTE); \ do { \
do { EXTRA } while (0); \ EXTRA \
} \ } while (0); \
} \
struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n struct e_n_d__w_i_t_h__s_e_m_i_c_o_l_o_n
DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(specific::Vector3, vector, ;); DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(specific::Vector3, vector, ;);
DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(sot::MatrixHomogeneous, transform, ;); DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(sot::MatrixHomogeneous, transform, ;);
DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(specific::Twist, twist, ;); DG_BRIDGE_MAKE_STAMPED_SHPTR_IMPL(specific::Twist, twist, ;);
/// \brief If an impossible/unimplemented conversion is required, fail.
/// \brief If an impossible/unimplemented conversion is required, fail. ///
/// /// IMPORTANT, READ ME:
/// IMPORTANT, READ ME: ///
/// /// If the compiler generates an error in the following function,
/// If the compiler generates an error in the following function, /// this is /normal/.
/// this is /normal/. ///
/// /// This error means that either you try to use an undefined
/// This error means that either you try to use an undefined /// conversion. You can either fix your code or provide the wanted
/// conversion. You can either fix your code or provide the wanted /// conversion by updating this header.
/// conversion by updating this header. template <typename U, typename V>
template <typename U, typename V> inline void converter(U& dst, V& src) {
inline void converter (U& dst, V& src) // This will always fail if instantiated.
{ BOOST_STATIC_ASSERT(sizeof(U) == 0);
// This will always fail if instantiated. }
BOOST_STATIC_ASSERT (sizeof (U) == 0);
} typedef boost::posix_time::ptime ptime;
typedef boost::posix_time::seconds seconds;
typedef boost::posix_time::ptime ptime; typedef boost::posix_time::microseconds microseconds;
typedef boost::posix_time::seconds seconds; typedef boost::posix_time::time_duration time_duration;
typedef boost::posix_time::microseconds microseconds; typedef boost::gregorian::date date;
typedef boost::posix_time::time_duration time_duration;
typedef boost::gregorian::date date; boost::posix_time::ptime rosTimeToPtime(const ros::Time& rosTime) {
ptime time(date(1970, 1, 1),
boost::posix_time::ptime rosTimeToPtime (const ros::Time& rosTime) seconds(rosTime.sec) + microseconds(rosTime.nsec / 1000));
{ return time;
ptime time (date(1970,1,1), seconds (rosTime.sec) + }
microseconds (rosTime.nsec/1000));
return time; ros::Time pTimeToRostime(const boost::posix_time::ptime& time) {
} static ptime timeStart(date(1970, 1, 1));
time_duration diff = time - timeStart;
ros::Time pTimeToRostime (const boost::posix_time::ptime& time)
{ uint32_t sec = (unsigned int)diff.ticks() /
static ptime timeStart(date(1970,1,1)); (unsigned int)time_duration::rep_type::res_adjust();
time_duration diff = time - timeStart; uint32_t nsec = (unsigned int)diff.fractional_seconds();
uint32_t sec = diff.ticks ()/time_duration::rep_type::res_adjust (); return ros::Time(sec, nsec);
uint32_t nsec = diff.fractional_seconds(); }
} // end of namespace dynamicgraph.
return ros::Time (sec, nsec);
} #endif //! DYNAMIC_GRAPH_ROS_CONVERTER_HH
} // end of namespace dynamicgraph.
#endif //! DYNAMIC_GRAPH_ROS_CONVERTER_HH
from ros_publish import RosPublish # flake8: noqa
from ros_subscribe import RosSubscribe from .ros import RosPublish as RosImport
from ros_joint_state import RosJointState from .ros import RosSubscribe as RosExport
from robot_model import RosRobotModel from .ros_publish import RosPublish
from .ros_subscribe import RosSubscribe
from ros import Ros from .ros_queued_subscribe import RosQueuedSubscribe
# aliases, for retro compatibility
ros_import = ros_publish
ros_export = ros_subscribe
from ros import RosPublish as RosImport
from ros import RosSubscribe as RosExport
"""Word completion for GNU readline.
The completer completes keywords, built-ins and globals in a selectable
namespace (which defaults to __main__); when completing NAME.NAME..., it
evaluates (!) the expression up to the last dot and completes its attributes.
It's very cool to do "import sys" type "sys.", hit the completion key (twice),
and see the list of names defined by the sys module!
Tip: to use the tab key as the completion key, call
readline.parse_and_bind("tab: complete")
Notes:
- Exceptions raised by the completer function are *ignored* (and generally cause
the completion to fail). This is a feature -- since readline sets the tty
device in raw (or cbreak) mode, printing a traceback wouldn't work well
without some complicated hoopla to save, reset and restore the tty state.
- The evaluation of the NAME.NAME... form may cause arbitrary application
defined code to be executed if an object with a __getattr__ hook is found.
Since it is the responsibility of the application (or the user) to enable this
feature, I consider this an acceptable risk. More complicated expressions
(e.g. function calls or indexing operations) are *not* evaluated.
- GNU readline is also used by the built-in functions input() and
raw_input(), and thus these also benefit/suffer from the completer
features. Clearly an interactive application can benefit by
specifying its own completer function and using raw_input() for all
its input.
- When the original stdin is not a tty device, GNU readline is never
used, and this module (and the readline module) are silently inactive.
"""
import ast
__all__ = ["DGCompleter"]
class DGCompleter:
def __init__(self, client):
"""Create a new completer for the command line.
Completer([client]) -> completer instance.
Client is a ROS proxy to dynamic_graph run_command service.
Completer instances should be used as the completion mechanism of
readline via the set_completer() call:
readline.set_completer(Completer(client).complete)
"""
self.client = client
astr = "import readline"
self.client(astr)
astr = "from rlcompleter import Completer"
self.client(astr)
astr = "aCompleter=Completer()"
self.client(astr)
astr = "readline.set_completer(aCompleter.complete)"
self.client(astr)
astr = 'readline.parse_and_bind("tab: complete")'
self.client(astr)
def complete(self, text, state):
"""Return the next possible completion for 'text'.
readline.parse_and_bind("tab: complete")
This is called successively with state == 0, 1, 2, ... until it
returns None. The completion should begin with 'text'.
"""
astr = 'aCompleter.complete("' + text + '",' + str(state) + ")"
response = self.client(astr)
res2 = ast.literal_eval(response.result)
return res2
from ros_publish import RosPublish from .ros_publish import RosPublish
from ros_subscribe import RosSubscribe from .ros_subscribe import RosSubscribe
from ros_joint_state import RosJointState from .ros_time import RosTime
from ros_time import RosTime
from dynamic_graph import plug
class Ros(object): class Ros(object):
device = None device = None
rosPublish = None rosPublish = None
rosSubscribe = None rosSubscribe = None
rosJointState = None
# aliases, for retro compatibility # aliases, for retro compatibility
rosImport = None rosImport = None
rosExport = None rosExport = None
def __init__(self, robot, suffix = ''): def __init__(self, robot, suffix=""):
self.robot = robot self.robot = robot
self.rosPublish = RosPublish('rosPublish{0}'.format(suffix)) self.rosPublish = RosPublish("rosPublish{0}".format(suffix))
self.rosSubscribe = RosSubscribe('rosSubscribe{0}'.format(suffix)) self.rosSubscribe = RosSubscribe("rosSubscribe{0}".format(suffix))
self.rosJointState = RosJointState('rosJointState{0}'.format(suffix)) self.rosTime = RosTime("rosTime{0}".format(suffix))
self.rosJointState.retrieveJointNames(self.robot.dynamic.name)
self.rosTime = RosTime ('rosTime{0}'.format(suffix))
plug(self.robot.device.state, self.rosJointState.state) self.robot.device.after.addSignal("{0}.trigger".format(self.rosPublish.name))
self.robot.device.after.addSignal(
'{0}.trigger'.format(self.rosPublish.name))
self.robot.device.after.addSignal(
'{0}.trigger'.format(self.rosJointState.name))
# aliases, for retro compatibility # aliases, for retro compatibility
self.rosImport=self.rosPublish self.rosImport = self.rosPublish
self.rosExport=self.rosSubscribe self.rosExport = self.rosSubscribe
...@@ -4,64 +4,31 @@ ...@@ -4,64 +4,31 @@
* *
* CNRS * CNRS
* *
* This file is part of dynamic_graph_bridge.
* dynamic_graph_bridge 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.
* dynamic_graph_bridge 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 dynamic_graph_bridge. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <iostream> #include <ros/console.h>
#include <boost/thread/thread.hpp>
#include <boost/thread/condition.hpp>
#include "sot_loader.hh" #include <iostream>
boost::condition_variable cond; #define ENABLE_RT_LOG
boost::mutex mut; #include <dynamic-graph/real-time-logger.h>
void workThread(SotLoader *aSotLoader) #include <dynamic_graph_bridge/sot_loader.hh>
{
{
boost::lock_guard<boost::mutex> lock(mut);
}
while(aSotLoader->isDynamicGraphStopped())
{
usleep(5000);
}
while(!aSotLoader->isDynamicGraphStopped())
{
aSotLoader->oneIteration();
usleep(5000);
}
cond.notify_all();
ros::waitForShutdown();
}
int main(int argc, char *argv[]) {
::dynamicgraph::RealTimeLogger::instance().addOutputStream(
::dynamicgraph::LoggerStreamPtr_t(
new dynamicgraph::LoggerIOStream(std::cout)));
int main(int argc, char *argv[])
{
ros::init(argc, argv, "sot_ros_encapsulator"); ros::init(argc, argv, "sot_ros_encapsulator");
SotLoader aSotLoader; SotLoader aSotLoader;
if (aSotLoader.parseOptions(argc,argv)<0) if (aSotLoader.parseOptions(argc, argv) < 0) return -1;
return -1;
ros::NodeHandle n;
ros::ServiceServer service = n.advertiseService("start_dynamic_graph",
&SotLoader::start_dg,
&aSotLoader);
ROS_INFO("Ready to start dynamic graph.");
boost::thread thr(workThread,&aSotLoader); // Advertize service "(start|stop)_dynamic_graph" and
// load parameter "robot_description in SoT.
aSotLoader.initializeRosNode(argc, argv);
// Load dynamic library and run python prologue.
aSotLoader.Initialization();
boost::unique_lock<boost::mutex> lock(mut); ros::waitForShutdown();
cond.wait(lock); return 0;
ros::spin();
} }
#include <dynamic_graph_bridge/ros_init.hh>
#include <dynamic_graph_bridge/ros_interpreter.hh>
int main ()
{
// we spin explicitly so we do not need an async spinner here.
ros::NodeHandle& nodeHandle = dynamicgraph::rosInit (false);
dynamicgraph::Interpreter interpreter (nodeHandle);
ros::spin ();
}
#include "robot_model.hh"
#include <dynamic-graph/all-commands.h>
#include <dynamic-graph/factory.h>
#include <jrl/dynamics/urdf/parser.hh>
#include "dynamic_graph_bridge/ros_init.hh"
namespace dynamicgraph
{
RosRobotModel::RosRobotModel(const std::string& name)
: Dynamic(name,false),
jointsParameterName_("jrl_map"),
ns_("sot_controller")
{
std::string docstring;
docstring =
"\n"
" Load the robot model from the parameter server.\n"
"\n"
" This is the recommended method.\n"
"\n";
addCommand("loadFromParameterServer", command::makeCommandVoid0(*this,&RosRobotModel::loadFromParameterServer,docstring));
docstring =
"\n"
" Load the robot model from an URDF file.\n"
"\n";
addCommand("loadUrdf", command::makeCommandVoid1(*this,&RosRobotModel::loadUrdf,docstring));
docstring =
"\n"
" Set the controller namespace."
"\n";
addCommand("setNamespace", command::makeCommandVoid1(*this,&RosRobotModel::setNamespace,docstring));
docstring =
"\n"
" Get current configuration of the robot.\n"
"\n";
addCommand ("curConf", new command::Getter<RosRobotModel,Vector> (*this,&RosRobotModel::curConf,docstring));
docstring =
"\n"
" Maps a link name in the URDF parser to actual robot link name.\n"
"\n";
addCommand ("addJointMapping", command::makeCommandVoid2(*this,&RosRobotModel::addJointMapping,docstring));
}
RosRobotModel::~RosRobotModel()
{}
void RosRobotModel::loadUrdf (const std::string& filename)
{
jrl::dynamics::urdf::Parser parser;
std::map<std::string, std::string>::const_iterator it = specialJoints_.begin();
for (;it!=specialJoints_.end();++it) {
parser.specifyREPName(it->first, it->second);
}
rosInit (false);
m_HDR = parser.parse(filename);
ros::NodeHandle nh(ns_);
nh.setParam(jointsParameterName_, parser.JointsNamesByRank_);
}
void RosRobotModel::setNamespace (const std::string& ns)
{
ns_ = ns;
}
void RosRobotModel::loadFromParameterServer()
{
jrl::dynamics::urdf::Parser parser;
std::map<std::string, std::string>::const_iterator it = specialJoints_.begin();
for (;it!=specialJoints_.end();++it) {
parser.specifyREPName(it->first, it->second);
}
rosInit (false);
std::string robotDescription;
ros::param::param<std::string> ("/robot_description", robotDescription, "");
if (robotDescription.empty ())
throw std::runtime_error("No model available as ROS parameter. Fail.");
m_HDR = parser.parseStream (robotDescription);
ros::NodeHandle nh(ns_);
nh.setParam(jointsParameterName_, parser.JointsNamesByRank_);
}
namespace
{
vectorN convertVector(const ml::Vector& v)
{
vectorN res (v.size());
for (unsigned i = 0; i < v.size(); ++i)
res[i] = v(i);
return res;
}
ml::Vector convertVector(const vectorN& v)
{
ml::Vector res;
res.resize(v.size());
for (unsigned i = 0; i < v.size(); ++i)
res(i) = v[i];
return res;
}
} // end of anonymous namespace.
Vector RosRobotModel::curConf() const
{
// The first 6 dofs are associated to the Freeflyer frame
// Freeflyer reference frame should be the same as global
// frame so that operational point positions correspond to
// position in freeflyer frame.
XmlRpc::XmlRpcValue ffpose;
ros::NodeHandle nh(ns_);
std::string param_name = "ffpose";
if (nh.hasParam(param_name)){
nh.getParam(param_name, ffpose);
ROS_ASSERT(ffpose.getType() == XmlRpc::XmlRpcValue::TypeArray);
ROS_ASSERT(ffpose.size() == 6);
for (int32_t i = 0; i < ffpose.size(); ++i)
{
ROS_ASSERT(ffpose[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
}
}
else
{
ffpose.setSize(6);
for (int32_t i = 0; i < ffpose.size(); ++i)
ffpose[i] = 0.0;
}
if (!m_HDR )
throw std::runtime_error ("no robot loaded");
else {
vectorN currConf = m_HDR->currentConfiguration();
Vector res;
res = convertVector(currConf);
for (int32_t i = 0; i < ffpose.size(); ++i)
res(i) = static_cast<double>(ffpose[i]);
return res;
}
}
void
RosRobotModel::addJointMapping(const std::string &link, const std::string &repName)
{
specialJoints_[link] = repName;
}
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosRobotModel, "RosRobotModel");
} // end of namespace dynamicgraph.
#ifndef DYNAMIC_GRAPH_BRIDGE_ROBOT_MODEL_HH
# define DYNAMIC_GRAPH_BRIDGE_ROBOT_MODEL_HH
# include <string>
#include <sot-dynamic/dynamic.h>
#include <dynamic-graph/linear-algebra.h>
#include "XmlRpcValue.h"
namespace dynamicgraph
{
class RosRobotModel;
/// \brief This entity load either the current model available in
/// the robot_description parameter or a specified file and build
/// a Dynamic entity
///
/// This relies on jrl_dynamics_urdf to load the model and jrl-dynamics
/// to realize the computation.
class RosRobotModel : public sot::Dynamic
{
DYNAMIC_GRAPH_ENTITY_DECL();
public:
RosRobotModel(const std::string& n);
virtual ~RosRobotModel();
void loadUrdf(const std::string& filename);
void setNamespace (const std::string& ns);
void loadFromParameterServer();
Vector curConf() const;
void addJointMapping(const std::string& link, const std::string& repName);
protected:
unsigned getDimension () const
{
if (!m_HDR)
throw std::runtime_error ("no robot loaded");
return m_HDR->numberDof();
}
private:
/// \brief Name of the parameter where the joints list will be published
std::string jointsParameterName_;
/// \brief Name of the controller namespace
std::string ns_;
/// \brief Special joints map for the parser
std::map<std::string, std::string> specialJoints_;
};
} // end of namespace dynamicgraph.
#endif //! DYNAMIC_GRAPH_BRIDGE_ROBOT_MODEL_HH
#include <stdexcept> #include "dynamic_graph_bridge/ros_init.hh"
#include <boost/make_shared.hpp> #include <boost/make_shared.hpp>
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
#include <stdexcept>
#include "dynamic_graph_bridge/ros_init.hh" namespace dynamicgraph {
struct GlobalRos {
namespace dynamicgraph ~GlobalRos() {
{ if (spinner) spinner->stop();
struct GlobalRos if (nodeHandle) nodeHandle->shutdown();
{ }
~GlobalRos ()
{
if (spinner)
spinner->stop ();
if (nodeHandle)
nodeHandle->shutdown ();
}
boost::shared_ptr<ros::NodeHandle> nodeHandle; boost::shared_ptr<ros::NodeHandle> nodeHandle;
boost::shared_ptr<ros::AsyncSpinner> spinner; boost::shared_ptr<ros::AsyncSpinner> spinner;
boost::shared_ptr<ros::MultiThreadedSpinner> mtSpinner; boost::shared_ptr<ros::MultiThreadedSpinner> mtSpinner;
}; };
GlobalRos ros; GlobalRos ros;
ros::NodeHandle& rosInit (bool createAsyncSpinner, bool createMultiThreadedSpinner) ros::NodeHandle& rosInit(bool createAsyncSpinner,
{ bool createMultiThreadedSpinner) {
if (!ros.nodeHandle) if (!ros.nodeHandle) {
{ int argc = 1;
int argc = 1; char* arg0 = strdup("dynamic_graph_bridge");
char* arg0 = strdup("dynamic_graph_bridge"); char* argv[] = {arg0, 0};
char* argv[] = {arg0, 0}; ros::init(argc, argv, "dynamic_graph_bridge");
ros::init(argc, argv, "dynamic_graph_bridge"); free(arg0);
free (arg0);
ros.nodeHandle = boost::make_shared<ros::NodeHandle> (""); ros.nodeHandle = boost::make_shared<ros::NodeHandle>("");
}
if (!ros.spinner && createAsyncSpinner)
{
ros.spinner = boost::make_shared<ros::AsyncSpinner> (4);
ros.spinner->start ();
}
else
{
if (!ros.mtSpinner && createMultiThreadedSpinner)
{
ros.mtSpinner = boost::make_shared<ros::MultiThreadedSpinner>(4);
}
}
return *ros.nodeHandle;
} }
if (!ros.spinner && createAsyncSpinner) {
ros.spinner = boost::make_shared<ros::AsyncSpinner>(4);
ros::AsyncSpinner& spinner () // Change the thread's scheduler from real-time to normal and reduce its
{ // priority
if (!ros.spinner) int oldThreadPolicy, newThreadPolicy;
throw std::runtime_error ("spinner has not been created"); struct sched_param oldThreadParam, newThreadParam;
return *ros.spinner; if (pthread_getschedparam(pthread_self(), &oldThreadPolicy,
} &oldThreadParam) == 0) {
newThreadPolicy = SCHED_OTHER;
newThreadParam = oldThreadParam;
newThreadParam.sched_priority -=
5; // Arbitrary number, TODO: choose via param/file?
if (newThreadParam.sched_priority <
sched_get_priority_min(newThreadPolicy))
newThreadParam.sched_priority = sched_get_priority_min(newThreadPolicy);
pthread_setschedparam(pthread_self(), newThreadPolicy, &newThreadParam);
}
// AsyncSpinners are created with the reduced priority
ros.spinner->start();
ros::MultiThreadedSpinner& mtSpinner () // Switch the priority of the parent thread (this thread) back to real-time.
{ pthread_setschedparam(pthread_self(), oldThreadPolicy, &oldThreadParam);
if (!ros.mtSpinner) } else {
throw std::runtime_error ("spinner has not been created"); if (!ros.mtSpinner && createMultiThreadedSpinner) {
return *ros.mtSpinner; // Seems not to be used.
// If we need to reduce its threads priority, it needs to be done before
// calling the MultiThreadedSpinner::spin() method
ros.mtSpinner = boost::make_shared<ros::MultiThreadedSpinner>(4);
}
} }
return *ros.nodeHandle;
}
ros::AsyncSpinner& spinner() {
if (!ros.spinner) throw std::runtime_error("spinner has not been created");
return *ros.spinner;
}
ros::MultiThreadedSpinner& mtSpinner() {
if (!ros.mtSpinner) throw std::runtime_error("spinner has not been created");
return *ros.mtSpinner;
}
} // end of namespace dynamicgraph. } // end of namespace dynamicgraph.
#include "dynamic_graph_bridge/ros_interpreter.hh" #include "dynamic_graph_bridge/ros_interpreter.hh"
namespace dynamicgraph namespace dynamicgraph {
{ static const int queueSize = 5;
static const int queueSize = 5;
Interpreter::Interpreter(ros::NodeHandle& nodeHandle)
Interpreter::Interpreter (ros::NodeHandle& nodeHandle) : interpreter_(),
: interpreter_ (), nodeHandle_(nodeHandle),
nodeHandle_ (nodeHandle), runCommandSrv_(),
runCommandSrv_ () runPythonFileSrv_() {}
{
void Interpreter::startRosService() {
runCommandCallback_t runCommandCb =
boost::bind(&Interpreter::runCommandCallback, this, _1, _2);
runCommandSrv_ = nodeHandle_.advertiseService("run_command", runCommandCb);
runPythonFileCallback_t runPythonFileCb =
boost::bind(&Interpreter::runPythonFileCallback, this, _1, _2);
runPythonFileSrv_ =
nodeHandle_.advertiseService("run_script", runPythonFileCb);
}
bool Interpreter::runCommandCallback(
dynamic_graph_bridge_msgs::RunCommand::Request& req,
dynamic_graph_bridge_msgs::RunCommand::Response& res) {
interpreter_.python(req.input, res.result, res.standardoutput,
res.standarderror);
return true;
}
bool Interpreter::runPythonFileCallback(
dynamic_graph_bridge_msgs::RunPythonFile::Request& req,
dynamic_graph_bridge_msgs::RunPythonFile::Response& res) {
interpreter_.runPythonFile(req.input);
res.result = "File parsed"; // FIX: It is just an echo, is there a way to
// have a feedback?
return true;
}
void Interpreter::runCommand(const std::string& command, std::string& result,
std::string& out, std::string& err) {
interpreter_.python(command, result, out, err);
if (err.size() > 0) {
ROS_ERROR(err.c_str());
} }
}
void Interpreter::startRosService () void Interpreter::runPythonFile(std::string ifilename) {
{ interpreter_.runPythonFile(ifilename);
runCommandCallback_t runCommandCb = }
boost::bind (&Interpreter::runCommandCallback, this, _1, _2);
runCommandSrv_ =
nodeHandle_.advertiseService ("run_command", runCommandCb);
}
bool
Interpreter::runCommandCallback
(dynamic_graph_bridge::RunCommand::Request& req,
dynamic_graph_bridge::RunCommand::Response& res)
{
interpreter_.python(req.input, res.result, res.stdout, res.stderr);
return true;
}
std::string
Interpreter::runCommand
(const std::string& command)
{
return interpreter_.python(command);
}
void Interpreter::runCommand
(const std::string & command,
std::string &result,
std::string &out,
std::string &err)
{
interpreter_.python(command, result, out, err);
}
} // end of namespace dynamicgraph.
} // end of namespace dynamicgraph.
#include <boost/assign.hpp>
#include <boost/bind.hpp>
#include <boost/format.hpp>
#include <dynamic-graph/command.h>
#include <dynamic-graph/factory.h>
#include <dynamic-graph/pool.h>
#include <sot-dynamic/dynamic.h>
#include "dynamic_graph_bridge/ros_init.hh"
#include "ros_joint_state.hh"
#include "sot_to_ros.hh"
namespace dynamicgraph
{
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(RosJointState, "RosJointState");
const double RosJointState::ROS_JOINT_STATE_PUBLISHER_RATE = 0.01;
namespace command
{
using ::dynamicgraph::command::Command;
using ::dynamicgraph::command::Value;
class RetrieveJointNames : public Command
{
public:
RetrieveJointNames (RosJointState& entity,
const std::string& docstring);
virtual Value doExecute ();
};
RetrieveJointNames::RetrieveJointNames
(RosJointState& entity, const std::string& docstring)
: Command (entity, boost::assign::list_of (Value::STRING), docstring)
{}
namespace
{
void
buildJointNames (sensor_msgs::JointState& jointState, CjrlJoint* joint)
{
if (!joint)
return;
// Ignore anchors.
if (joint->numberDof() != 0)
{
// If we only have one dof, the dof name is the joint name.
if (joint->numberDof() == 1)
{
jointState.name[joint->rankInConfiguration()] =
joint->getName();
}
// ...otherwise, the dof name is the joint name on which
// the dof id is appended.
else
for (unsigned i = 0; i < joint->numberDof(); ++i)
{
boost::format fmt("%1%_%2%");
fmt % joint->getName();
fmt % i;
jointState.name[joint->rankInConfiguration() + i] =
fmt.str();
}
}
for (unsigned i = 0; i < joint->countChildJoints (); ++i)
buildJointNames (jointState, joint->childJoint (i));
}
} // end of anonymous namespace
Value RetrieveJointNames::doExecute ()
{
RosJointState& entity = static_cast<RosJointState&> (owner ());
std::vector<Value> values = getParameterValues ();
std::string name = values[0].value ();
if (!dynamicgraph::PoolStorage::getInstance ()->existEntity (name))
{
std::cerr << "invalid entity name" << std::endl;
return Value ();
}
dynamicgraph::sot::Dynamic* dynamic =
dynamic_cast<dynamicgraph::sot::Dynamic*>
(&dynamicgraph::PoolStorage::getInstance ()->getEntity (name));
if (!dynamic)
{
std::cerr << "entity is not a Dynamic entity" << std::endl;
return Value ();
}
CjrlHumanoidDynamicRobot* robot = dynamic->m_HDR;
if (!robot)
{
std::cerr << "no robot in the dynamic entity" << std::endl;
return Value ();
}
entity.jointState ().name.resize (robot->numberDof());
buildJointNames (entity.jointState (), robot->rootJoint());
return Value ();
}
} // end of namespace command.
RosJointState::RosJointState (const std::string& n)
: Entity (n),
// do not use callbacks, so do not create a useless spinner
nh_ (rosInit (false)),
state_ (0, MAKE_SIGNAL_STRING(name, true, "Vector", "state")),
publisher_ (nh_, "dynamic_graph/joint_states", 5),
jointState_ (),
trigger_ (boost::bind (&RosJointState::trigger, this, _1, _2),
sotNOSIGNAL,
MAKE_SIGNAL_STRING(name, true, "int", "trigger")),
rate_ (ROS_JOINT_STATE_PUBLISHER_RATE),
lastPublicated_ ()
{
try {
lastPublicated_ = ros::Time::now ();
} catch (const std::exception& exc) {
throw std::runtime_error ("Failed to call ros::Time::now ():" +
std::string (exc.what ()));
}
signalRegistration (state_ << trigger_);
trigger_.setNeedUpdateFromAllChildren (true);
// Fill header.
jointState_.header.seq = 0;
jointState_.header.stamp.sec = 0;
jointState_.header.stamp.nsec = 0;
jointState_.header.frame_id = "";
std::string docstring =
"\n"
" Retrieve joint names using robot model contained in a Dynamic entity\n"
"\n"
" Input:\n"
" - dynamic entity name (i.e. robot.dynamic.name)\n"
"\n";
addCommand ("retrieveJointNames",
new command::RetrieveJointNames (*this, docstring));
}
RosJointState::~RosJointState ()
{}
int&
RosJointState::trigger (int& dummy, int t)
{
ros::Duration dt = ros::Time::now () - lastPublicated_;
if (dt > rate_ && publisher_.trylock ())
{
lastPublicated_ = ros::Time::now ();
// State size without the free floating.
std::size_t s = state_.access (t).size ();
// Safety check: if data are inconsistent, clear
// the joint names to avoid sending erroneous data.
// This should not happen unless you change
// the robot model at run-time.
if (s != jointState_.name.size())
jointState_.name.clear();
// Update header.
++jointState_.header.seq;
ros::Time now = ros::Time::now ();
jointState_.header.stamp.sec = now.sec;
jointState_.header.stamp.nsec = now.nsec;
// Fill position.
jointState_.position.resize (s);
for (std::size_t i = 0; i < s; ++i)
jointState_.position[i] = state_.access (t) (i);
publisher_.msg_ = jointState_;
publisher_.unlockAndPublish ();
}
return dummy;
}
} // end of namespace dynamicgraph.
#ifndef DYNAMIC_GRAPH_JOINT_STATE_HH
# define DYNAMIC_GRAPH_JOINT_STATE_HH
# include <dynamic-graph/entity.h>
# include <dynamic-graph/signal-ptr.h>
# include <dynamic-graph/signal-time-dependent.h>
# include <ros/ros.h>
# include <realtime_tools/realtime_publisher.h>
# include <sensor_msgs/JointState.h>
# include "converter.hh"
# include "sot_to_ros.hh"
namespace dynamicgraph
{
/// \brief Publish current robot configuration to ROS.
class RosJointState : public dynamicgraph::Entity
{
DYNAMIC_GRAPH_ENTITY_DECL();
public:
/// \brief Vector input signal.
typedef SignalPtr<ml::Vector, int> signalVectorIn_t;
static const double ROS_JOINT_STATE_PUBLISHER_RATE;
RosJointState (const std::string& n);
virtual ~RosJointState ();
int& trigger (int&, int);
sensor_msgs::JointState& jointState ()
{
return jointState_;
}
private:
ros::NodeHandle& nh_;
signalVectorIn_t state_;
realtime_tools::RealtimePublisher<sensor_msgs::JointState> publisher_;
sensor_msgs::JointState jointState_;
dynamicgraph::SignalTimeDependent<int,int> trigger_;
ros::Duration rate_;
ros::Time lastPublicated_;
};
} // end of namespace dynamicgraph.
#endif //! DYNAMIC_GRAPH_JOINT_STATE_HH
#include <pinocchio/fwd.hpp>
// include pinocchio first
//
#include <ros/ros.h>
#include <urdf_parser/urdf_parser.h>
#include <boost/make_shared.hpp>
#include <boost/shared_ptr.hpp>
#include <sot/core/robot-utils.hh>
#include <stdexcept>
#include "dynamic_graph_bridge/ros_parameter.hh"
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/parsers/urdf.hpp"
namespace dynamicgraph {
bool parameter_server_read_robot_description() {
ros::NodeHandle nh;
if (!nh.hasParam("/robot_description")) {
ROS_ERROR("No /robot_description parameter");
return false;
}
std::string robot_description;
std::string parameter_name("/robot_description");
nh.getParam(parameter_name, robot_description);
std::string model_name("robot");
// Search for the robot util related to robot_name.
sot::RobotUtilShrPtr aRobotUtil = sot::getRobotUtil(model_name);
// If does not exist then it is created.
if (aRobotUtil == sot::RefVoidRobotUtil())
aRobotUtil = sot::createRobotUtil(model_name);
// If the creation is fine
if (aRobotUtil != sot::RefVoidRobotUtil()) {
// Then set the robot model.
aRobotUtil->set_parameter(parameter_name, robot_description);
ROS_INFO("Set parameter_name : %s.", parameter_name.c_str());
// Everything went fine.
return true;
}
ROS_ERROR("Wrong initialization of parameter_name %s",
parameter_name.c_str());
// Otherwise something went wrong.
return false;
}
} // namespace dynamicgraph
#include <dynamic-graph/python/module.hh>
#include "ros_publish.hh"
namespace dg = dynamicgraph;
BOOST_PYTHON_MODULE(wrap) {
bp::import("dynamic_graph");
dg::python::exposeEntity<dg::RosPublish, bp::bases<dg::Entity>,
dg::python::AddCommands>()
.def("clear", &dg::RosPublish::clear,
"Remove all signals writing data to a ROS topic")
.def("rm", &dg::RosPublish::rm,
"Remove a signal writing data to a ROS topic",
bp::args("signal_name"))
.def("list", &dg::RosPublish::list,
"List signals writing data to a ROS topic");
}