Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[tf_relay] add tf_relay package #1698

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
68 changes: 68 additions & 0 deletions jsk_coordination_system/tf_relay/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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()
30 changes: 30 additions & 0 deletions jsk_coordination_system/tf_relay/README.md
Original file line number Diff line number Diff line change
@@ -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.
147 changes: 147 additions & 0 deletions jsk_coordination_system/tf_relay/config/tf_relay_sample.rviz
Original file line number Diff line number Diff line change
@@ -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: <Fixed 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: <Fixed 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
63 changes: 63 additions & 0 deletions jsk_coordination_system/tf_relay/include/tf_relay/tf_relay.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
#ifndef TF_RELAY_TF_RELAY_H__
#define TF_RELAY_TF_RELAY_H__

// Standaerd C++ Library
#include <iostream>
// ROS
#include <ros/ros.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
// ROS message
#include <geometry_msgs/TransformStamped.h>
// Boost
#include <boost/bind.hpp>

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
38 changes: 38 additions & 0 deletions jsk_coordination_system/tf_relay/launch/tf_relay_sample.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<launch>
<arg name="use_gui" default="true"/>

<node
pkg="tf2_ros"
type="static_transform_publisher"
name="transform_publisher_a_to_b"
args="1 0 0 0 0 0 frame_a frame_b"
/>

<node
pkg="tf2_ros"
type="static_transform_publisher"
name="transform_publisher_b_to_c"
args="0 0 1 0 0 0 frame_b frame_c"
/>

<node
pkg="tf_relay"
type="tf_relay"
name="tf_relay_node"
>
<rosparam>
fixed_frame_id: 'frame_a'
reference_frame_id: 'frame_c'
output_frame_id: 'frame_relayed'
</rosparam>
</node>

<node
pkg="rviz"
type="rviz"
name="$(anon rviz)"
args="-d $(find tf_relay)/config/tf_relay_sample.rviz"
if="$(arg use_gui)"
/>

</launch>
23 changes: 23 additions & 0 deletions jsk_coordination_system/tf_relay/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<package format="2">
<name>tf_relay</name>
<version>2.2.11</version>
<description>The tf_relay package</description>

<maintainer email="[email protected]">Kei Okada</maintainer>
<author email="[email protected]">Koki Shinjo</author>

<license>BSD</license>

<build_depend>boost</build_depend>
<depend>roscpp</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>geometry_msgs</depend>
<buildtool_depend>catkin</buildtool_depend>

<test_depend>rostest</test_depend>

<export>
</export>
</package>
Loading