ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform lookups ( see also #q258116 ). There aren't a lot of examples available however.

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core.

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

I'll find or make a C++ example and update this.

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform lookups ( see also #q258116 ). There aren't a lot of examples available however.

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core.

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

I'll find or make a C++ example and update this.

this, or link to one- I think there are more C++ examples online than python.

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform lookups ( see also #q258116 ). There aren't a lot of examples available however.

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core.. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

I'll find or make a C++ example and update this, or link to one- I think there are more C++ examples online than python.

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

I'll find or make a C++ example and update this, or link to one- I think there are more C++ examples online than python.

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

I'll find or make a C++ example and update this, or link to one- I think there are more C++ examples online than python.

C++

Haven't tested this yet but it is very similar to python:

tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
t1s.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority", is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1", ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
t1s.child_frame_id tss.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority", is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1", "frame1",
    ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
tss.child_frame_id ts1.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority", is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1",
    ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

#include <tf2/buffer_core.h>
...
tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
ts1.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority", is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1",
    ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

#include <tf2/buffer_core.h>
...
tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
ts1.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority", "default_authority",
    is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1",
    ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print dir(buffer_core)
print(dir(buffer_core))
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print a
print(a)
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print b
print(b)
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print buffer_core.lookup_transform_core('map', print(buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0))
rospy.Time(0)))

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

#include <tf2/buffer_core.h>
...
tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
ts1.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority",
    is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1",
    ros::Time(0));

BufferCore is the best way to do it while also maintaining a similar api to regular tf transform sets and lookups ( see also #q258116 ). There aren't a lot of examples available however.

Python

Here is a simple python example (I adapted it from http://docs.ros.org/diamondback/api/tf2/html/python/tf2.html where the api is different, but did the example survive into kinetic somewhere? I also had to look at /opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/buffer.py)

#!/usr/bin/env python
import rospy
import tf2_ros
from geometry_msgs.msg import TransformStamped

buffer_core = tf2_ros.BufferCore(rospy.Duration(10.0))
ts1 = TransformStamped()
ts1.header.stamp = rospy.Time(0)
ts1.header.frame_id = 'map'
ts1.child_frame_id = 'frame1'
ts1.transform.translation.x = 2.71828183
ts1.transform.rotation.w = 1.0
buffer_core.set_transform(ts1, "default_authority")

# print(dir(buffer_core))
a = buffer_core.lookup_transform_core('map', 'frame1', rospy.Time(0))
print(a)
# ((2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))
b = buffer_core.lookup_transform_core('frame1', 'map', rospy.Time(0))
print(b)
# ((-2.71828183, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0))

ts2 = TransformStamped()
ts2.header.stamp = rospy.Time(0)
ts2.header.frame_id = 'frame1'
ts2.child_frame_id = 'frame2'
ts2.transform.translation.y = 0.5
ts2.transform.rotation.w = 1.0
buffer_core.set_transform(ts2, "default_authority")

print(buffer_core.lookup_transform_core('map', 'frame2', rospy.Time(0)))

https://github.com/lucasw/tf_demo/blob/master/scripts/buffer_core_demo.py

I'm not sure why there isn't a lookup_transform, just lookup_transform_core. Maybe I should be using a BufferClient?

Rotations can be handled with transforms3d/transformations.py, I'll update the above with an example of that.

C++

Haven't tested this yet but it is very similar to python:

#include <tf2/buffer_core.h>
...
tf2::BufferCore buffer_core;
geometry_msgs::TransformStamped ts1;
ts1.header.frame_id = "map";
ts1.child_frame_id = "frame1";
ts1.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0.32, 0);
const bool is_static = true;
buffer_core.setTransform(ts1, "default_authority",
    is_static);
geometry_msgs::TransformStamped ts_lookup;
ts_lookup = buffer_core.lookupTransform("map", "frame1",
    ros::Time(0));