diff --git a/jsk_coordination_system/tf_relay/CMakeLists.txt b/jsk_coordination_system/tf_relay/CMakeLists.txt new file mode 100644 index 000000000..058a651ba --- /dev/null +++ b/jsk_coordination_system/tf_relay/CMakeLists.txt @@ -0,0 +1,68 @@ +cmake_minimum_required(VERSION 2.8.3) +project(tf_relay) + +add_compile_options(-std=c++11) + +find_package(catkin REQUIRED COMPONENTS + roscpp + tf2 + tf2_ros + geometry_msgs +) + +find_package(Boost REQUIRED) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES tf_relay + CATKIN_DEPENDS + roscpp + tf2 + tf2_ros + geometry_msgs + DEPENDS + Boost +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_executable(tf_relay + src/tf_relay_node.cpp + src/tf_relay.cpp +) +target_link_libraries(tf_relay + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + + + +# +# Install +# +install(TARGETS tf_relay + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config +) + + + +# +# Testing +# +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_rostest(test/test_tf_relay.test) +endif() diff --git a/jsk_coordination_system/tf_relay/README.md b/jsk_coordination_system/tf_relay/README.md new file mode 100644 index 000000000..e278ac644 --- /dev/null +++ b/jsk_coordination_system/tf_relay/README.md @@ -0,0 +1,30 @@ +# tf_relay + +This node broadcasts transforms from a given fixed frame to a given output frame which is the same as reference frame in specified duraiton even when reference frame is not broadcasted. + + +## Parameters + +- '~max_duration' ( double, default: 5.0 ) + +cache duration for tf2 buffer. + +- '~timeout_duration' ( double, default: 0.05 ) + +timeout duration for lookuptransform of tf. + +- '~timer_duration' ( double, default: 0.1 ) + +spin duration for main process + +- '~reference_frame_id" ( string, default: 'reference_frame' ) + +tf frame_id of reference frame. + +- '~output_frame_id' ( string, default: 'output_frame' ) + +tf frame_id of output frame. + +- '~fixed_frame_id' ( string, default: 'fixed_frame' ) + +tf frame_id of fixed frame. diff --git a/jsk_coordination_system/tf_relay/config/tf_relay_sample.rviz b/jsk_coordination_system/tf_relay/config/tf_relay_sample.rviz new file mode 100644 index 000000000..b7eb3017a --- /dev/null +++ b/jsk_coordination_system/tf_relay/config/tf_relay_sample.rviz @@ -0,0 +1,147 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 728 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + frame_a: + Value: true + frame_b: + Value: true + frame_c: + Value: true + frame_c_relayed: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + frame_a: + frame_b: + frame_c: + {} + frame_c_relayed: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: frame_a + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 5.23662805557251 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.49539828300476074 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.6503981351852417 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000015600000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003c00000003efc0100000002fb0000000800540069006d00650100000000000003c0000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000002640000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 960 + X: 0 + Y: 27 diff --git a/jsk_coordination_system/tf_relay/include/tf_relay/tf_relay.h b/jsk_coordination_system/tf_relay/include/tf_relay/tf_relay.h new file mode 100644 index 000000000..7542370e9 --- /dev/null +++ b/jsk_coordination_system/tf_relay/include/tf_relay/tf_relay.h @@ -0,0 +1,63 @@ +#ifndef TF_RELAY_TF_RELAY_H__ +#define TF_RELAY_TF_RELAY_H__ + +// Standaerd C++ Library +#include +// ROS +#include +#include +#include +#include +// ROS message +#include +// Boost +#include + +namespace tf_relay { + + /** + * @brief The TFRelay class is for calculate and publish walking status of each foot + */ + class TFRelay + { + public: + + TFRelay( ros::NodeHandle &nh, + ros::NodeHandle &nh_private, + tf2_ros::Buffer &tf_buffer, + tf2_ros::TransformBroadcaster &tf_broadcaster ); + + /** + * @brief Main loop function. It will start spinner threads for subscribers and start main loop + * for calculation of commands to vibrators. + * @param nh ros::NodeHandle ros node handler + * @param nh_private ros::NodeHandle ros node handler with private namespace + * @param tf_buffer tf2_ros::Buffer tf2_ros buffer + */ + void spin(); + + private: + + /** + * ROS + */ + ros::NodeHandle& nh_; + ros::NodeHandle& nh_private_; + tf2_ros::Buffer& tf_buffer_; + tf2_ros::TransformBroadcaster& tf_broadcaster_; + std::string reference_frame_id_; + std::string output_frame_id_; + std::string fixed_frame_id_; + ros::Duration duration_timeout_; + bool identity_initialize_; + + bool initialized_; + + geometry_msgs::TransformStamped msg_transform_; + + void callbackTimerTF( const ros::TimerEvent& ); + }; + +} + +#endif diff --git a/jsk_coordination_system/tf_relay/launch/tf_relay_sample.launch b/jsk_coordination_system/tf_relay/launch/tf_relay_sample.launch new file mode 100644 index 000000000..52685362a --- /dev/null +++ b/jsk_coordination_system/tf_relay/launch/tf_relay_sample.launch @@ -0,0 +1,38 @@ + + + + + + + + + + fixed_frame_id: 'frame_a' + reference_frame_id: 'frame_c' + output_frame_id: 'frame_relayed' + + + + + + diff --git a/jsk_coordination_system/tf_relay/package.xml b/jsk_coordination_system/tf_relay/package.xml new file mode 100644 index 000000000..be0de0534 --- /dev/null +++ b/jsk_coordination_system/tf_relay/package.xml @@ -0,0 +1,23 @@ + + + tf_relay + 2.2.11 + The tf_relay package + + Kei Okada + Koki Shinjo + + BSD + + boost + roscpp + tf2 + tf2_ros + geometry_msgs + catkin + + rostest + + + + diff --git a/jsk_coordination_system/tf_relay/src/tf_relay.cpp b/jsk_coordination_system/tf_relay/src/tf_relay.cpp new file mode 100644 index 000000000..11b1fdaa1 --- /dev/null +++ b/jsk_coordination_system/tf_relay/src/tf_relay.cpp @@ -0,0 +1,108 @@ +// Standaerd C++ Library +#include +// ROS +#include +#include +#include +#include +// ROS message +#include +// Boost +#include +// USER +#include "tf_relay/tf_relay.h" + +namespace tf_relay { + + TFRelay::TFRelay( ros::NodeHandle &nh, + ros::NodeHandle &nh_private, + tf2_ros::Buffer &tf_buffer, + tf2_ros::TransformBroadcaster &tf_broadcaster ) + : nh_(nh), nh_private_(nh_private), tf_buffer_(tf_buffer), tf_broadcaster_(tf_broadcaster) + { + this->reference_frame_id_ = "reference_frame"; + if ( nh_private.hasParam("reference_frame_id") ) { + nh_private.getParam("reference_frame_id", this->reference_frame_id_); + } + + this->output_frame_id_ = "output_frame"; + if ( nh_private.hasParam("output_frame_id") ) { + nh_private.getParam("output_frame_id", this->output_frame_id_); + } + + this->fixed_frame_id_ = "fixed_frame"; + if ( nh_private.hasParam("fixed_frame_id") ) { + nh_private.getParam("fixed_frame_id", this->fixed_frame_id_); + } + + double timeout = 0.05; + if ( this->nh_private_.hasParam("timeout_duration") ) { + this->nh_private_.getParam("timeout_duration", timeout); + } + this->duration_timeout_ = ros::Duration(timeout); + + this->identity_initialize_ = false; + if ( this->nh_private_.hasParam("identity_initialize") ) { + this->nh_private_.getParam("identity_initialize", this->identity_initialize_); + } + + this->initialized_ = false; + + ROS_INFO("Initialization finished."); + } + + void TFRelay::spin() + { + double timer_duration = 0.1; + if ( this->nh_private_.hasParam("timer_duration") ) { + this->nh_private_.getParam("timer_duration", timer_duration); + } + + // start broadcaster timer + ros::Timer timer_tf = this->nh_.createTimer( + ros::Duration(timer_duration), + &TFRelay::callbackTimerTF, + this + ); + + ros::spin(); + } + + void TFRelay::callbackTimerTF( const ros::TimerEvent& ) + { + try { + geometry_msgs::TransformStamped temp_transform = + this->tf_buffer_.lookupTransform( + this->fixed_frame_id_, + this->reference_frame_id_, + ros::Time(0), + this->duration_timeout_ + ); + this->msg_transform_ = temp_transform; + this->msg_transform_.child_frame_id = this->output_frame_id_; + if ( not this->initialized_ ) { + this->initialized_ = true; + } + } catch (tf2::TransformException &ex) { + ROS_DEBUG("%s",ex.what()); + if ( this->identity_initialize_ ) { + this->msg_transform_.header.frame_id = this->fixed_frame_id_; + this->msg_transform_.child_frame_id = this->output_frame_id_; + this->msg_transform_.transform.translation.x = 0.0; + this->msg_transform_.transform.translation.y = 0.0; + this->msg_transform_.transform.translation.z = 0.0; + this->msg_transform_.transform.rotation.x = 0.0; + this->msg_transform_.transform.rotation.y = 0.0; + this->msg_transform_.transform.rotation.z = 0.0; + this->msg_transform_.transform.rotation.w = 1.0; + this->initialized_ = true; + } + } + if ( this->initialized_ ) { + this->msg_transform_.header.stamp = ros::Time::now(); + this->tf_broadcaster_.sendTransform(this->msg_transform_); + } + ROS_DEBUG("callback called."); + } + +} diff --git a/jsk_coordination_system/tf_relay/src/tf_relay_node.cpp b/jsk_coordination_system/tf_relay/src/tf_relay_node.cpp new file mode 100644 index 000000000..394b80d7d --- /dev/null +++ b/jsk_coordination_system/tf_relay/src/tf_relay_node.cpp @@ -0,0 +1,29 @@ +// ROS +#include +#include +#include +#include +// USER +#include "tf_relay/tf_relay.h" + +int main( int argc, char** argv ) +{ + // + ros::init( argc, argv, "tf_relay_node" ); + ros::NodeHandle nh; + ros::NodeHandle nh_private("~"); + + // + double max_duration; + nh_private.param("max_duration", max_duration, 5.0); + + // + ros::Duration tfduration(max_duration); + tf2_ros::Buffer tf_buffer(tfduration); + tf2_ros::TransformListener tf_listener(tf_buffer); + tf2_ros::TransformBroadcaster tf_broadcaster; + + // + tf_relay::TFRelay relay( nh, nh_private, tf_buffer, tf_broadcaster ); + relay.spin(); +} diff --git a/jsk_coordination_system/tf_relay/test/test_tf_relay.py b/jsk_coordination_system/tf_relay/test/test_tf_relay.py new file mode 100755 index 000000000..53b1958e6 --- /dev/null +++ b/jsk_coordination_system/tf_relay/test/test_tf_relay.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python + +PKG = 'tf_relay' +NAME = 'tf_relay_test' + +import rostest +import unittest +import sys + +import rospy +import tf2_ros + +class TestTFRelay(unittest.TestCase): + + def test_tf_relay(self): + + tf_buffer = tf2_ros.Buffer() + tf_listener = tf2_ros.TransformListener(tf_buffer) + + frame_id_a = 'frame_a' + frame_id_c = 'frame_c' + frame_id_relayed = 'frame_relayed' + + transform_a_to_c = tf_buffer.lookup_transform( + frame_id_a, + frame_id_c, + rospy.Time(), + rospy.Duration(10) + ) + transform_a_to_relayed = tf_buffer.lookup_transform( + frame_id_a, + frame_id_relayed, + rospy.Time(), + rospy.Duration(10) + ) + + self.assertEqual(transform_a_to_c.transform.translation.x, + transform_a_to_relayed.transform.translation.x) + self.assertEqual(transform_a_to_c.transform.translation.y, + transform_a_to_relayed.transform.translation.y) + self.assertEqual(transform_a_to_c.transform.translation.z, + transform_a_to_relayed.transform.translation.z) + self.assertEqual(transform_a_to_c.transform.rotation.x, + transform_a_to_relayed.transform.rotation.x) + self.assertEqual(transform_a_to_c.transform.rotation.y, + transform_a_to_relayed.transform.rotation.y) + self.assertEqual(transform_a_to_c.transform.rotation.z, + transform_a_to_relayed.transform.rotation.z) + self.assertEqual(transform_a_to_c.transform.rotation.w, + transform_a_to_relayed.transform.rotation.w) + + +if __name__ == '__main__': + rospy.init_node(NAME) + rostest.rosrun(PKG, NAME, TestTFRelay, sys.argv) diff --git a/jsk_coordination_system/tf_relay/test/test_tf_relay.test b/jsk_coordination_system/tf_relay/test/test_tf_relay.test new file mode 100644 index 000000000..00e7bdf76 --- /dev/null +++ b/jsk_coordination_system/tf_relay/test/test_tf_relay.test @@ -0,0 +1,7 @@ + + + + + + +