Skip to content

Commit

Permalink
Cleanup.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Aug 16, 2019
1 parent b5ca4ef commit ae6689e
Show file tree
Hide file tree
Showing 4 changed files with 22 additions and 21 deletions.
4 changes: 2 additions & 2 deletions tf2_py/package.xml
Expand Up @@ -5,7 +5,7 @@
<version>0.9.1</version>
<description>The tf2_py package</description>

<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<maintainer email="tfoote@osrfoundation.org">Tully Foote</maintainer>


Expand Down Expand Up @@ -35,7 +35,7 @@
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>geometry_msgs</test_depend>
<test_depend>rclpy</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
15 changes: 8 additions & 7 deletions tf2_py/src/tf2_py.cpp
Expand Up @@ -50,7 +50,7 @@ static PyObject *pModulerclpytime = NULL;
static PyObject *pModulebuiltininterfacesmsgs = NULL;
static PyObject *pModulegeometrymsgs = NULL;
static PyObject *tf2_exception = NULL;
static PyObject *tf2_connectivityexception = NULL, *tf2_lookupexception = NULL, *tf2_extrapolationexception = NULL,
static PyObject *tf2_connectivityexception = NULL, *tf2_lookupexception = NULL, *tf2_extrapolationexception = NULL,
*tf2_invalidargumentexception = NULL, *tf2_timeoutexception = NULL;

struct buffer_core_t {
Expand Down Expand Up @@ -124,6 +124,7 @@ static PyObject *transform_converter(const geometry_msgs::msg::TransformStamped*
PyObject *ptranslation = PyObject_GetAttrString(ptransform, "translation");
PyObject *protation = PyObject_GetAttrString(ptransform, "rotation");
Py_DECREF(ptransform);

PyObject_SetAttrString(pinst, "child_frame_id", stringToPython(transform->child_frame_id));

PyObject_SetAttrString(ptranslation, "x", PyFloat_FromDouble(transform->transform.translation.x));
Expand Down Expand Up @@ -178,7 +179,7 @@ static int rostime_converter(PyObject *obj, tf2::TimePoint *rt)
*rt = tf2::TimePoint(std::chrono::duration_cast<tf2::Duration>(ns));
return 1;
}

PyErr_SetString(PyExc_TypeError, "time must have sec and nanosec, or nanoseconds.");
return 0;
}
Expand All @@ -188,7 +189,7 @@ static int rosduration_converter(PyObject *obj, tf2::Duration *rt)
if(PyObject_HasAttrString(obj, "sec") && PyObject_HasAttrString(obj, "nanosec")) {
PyObject *sec = pythonBorrowAttrString(obj, "sec");
PyObject *nanosec = pythonBorrowAttrString(obj, "nanosec");
*rt = std::chrono::seconds(PyLong_AsLong(sec)) +
*rt = std::chrono::seconds(PyLong_AsLong(sec)) +
std::chrono::nanoseconds(PyLong_AsUnsignedLong(nanosec));
return 1;
}
Expand All @@ -200,7 +201,7 @@ static int rosduration_converter(PyObject *obj, tf2::Duration *rt)
*rt = std::chrono::duration_cast<tf2::Duration>(ns);
return 1;
}

PyErr_SetString(PyExc_TypeError, "time must have sec and nanosec, or nanoseconds.");
return 0;
}
Expand Down Expand Up @@ -330,7 +331,7 @@ static PyObject *getLatestCommonTime(PyObject *self, PyObject *args)
PyObject *nanoseconds = Py_BuildValue("i", time_msg.nanosec);
PyDict_SetItemString(kwargs, "seconds", seconds);
PyDict_SetItemString(kwargs, "nanoseconds", nanoseconds);

PyObject *ob = PyObject_Call(rclpy_time, args, kwargs);
Py_DECREF(nanoseconds);
Py_DECREF(seconds);
Expand Down Expand Up @@ -476,7 +477,7 @@ static PyObject *setTransform(PyObject *self, PyObject *args)
return NULL;

transform.header.stamp = toMsg(time);

PyObject *mtransform = pythonBorrowAttrString(py_transform, "transform");

PyObject *translation = pythonBorrowAttrString(mtransform, "translation");
Expand Down Expand Up @@ -640,7 +641,7 @@ bool staticInit() {
return false;
}

if(pModulerclpytime == NULL)
if(pModulerclpytime == NULL)
{
printf("Cannot load rclpy.time.Time module");
return false;
Expand Down
10 changes: 5 additions & 5 deletions tf2_ros/src/tf2_ros/buffer.py
Expand Up @@ -67,7 +67,7 @@ def __init__(self, cache_time = None, debug = True):
# try:
# m = rosgraph.masterapi.Master(rospy.get_name())
# m.lookupService('~tf2_frames')
# except (rosgraph.masterapi.Error, rosgraph.masterapi.Failure):
# except (rosgraph.masterapi.Error, rosgraph.masterapi.Failure):
# self.frame_server = rospy.Service('~tf2_frames', FrameGraph, self.__get_frames)

def __get_frames(self, req):
Expand Down Expand Up @@ -120,10 +120,10 @@ def can_transform(self, target_frame, source_frame, time, timeout=Duration(), re
clock = rclpy.timer.Clock()
if timeout != Duration():
start_time = clock.now()
# TODO(vinnamkim): rclpy.Rate is not ready
# TODO(vinnamkim): rclpy.Rate is not ready
# See https://github.com/ros2/rclpy/issues/186
# r = rospy.Rate(20)
while (clock.now() < start_time + timeout and
while (clock.now() < start_time + timeout and
not self.can_transform_core(target_frame, source_frame, time)[0] and
(clock.now() + Duration(seconds=3.0)) >= start_time): # big jumps in time are likely bag loops, so break for them
# r.sleep()
Expand Down Expand Up @@ -155,10 +155,10 @@ def can_transform_full(self, target_frame, target_time, source_frame, source_tim
clock = rclpy.timer.Clock()
if timeout != Duration():
start_time = clock.now()
# TODO(vinnamkim): rclpy.Rate is not ready
# TODO(vinnamkim): rclpy.Rate is not ready
# See https://github.com/ros2/rclpy/issues/186
# r = rospy.Rate(20)
while (clock.now() < start_time + timeout and
while (clock.now() < start_time + timeout and
not self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0] and
(clock.now() + Duration(seconds=3.0)) >= start_time): # big jumps in time are likely bag loops, so break for them
# r.sleep()
Expand Down
14 changes: 7 additions & 7 deletions tf2_ros/src/tf2_ros/buffer_client.py
Expand Up @@ -65,7 +65,7 @@ def __init__(self, node, ns, check_frequency = 10.0, timeout_padding = Duration(
self.action_client = ActionClient(node, LookupTransform, action_name=ns)
self.check_frequency = check_frequency
self.timeout_padding = timeout_padding

# lookup, simple api
def lookup_transform(self, target_frame, source_frame, time, timeout=Duration()):
"""
Expand Down Expand Up @@ -165,16 +165,16 @@ def __is_done(self, state):
def __process_goal(self, goal):
if not self.action_client.server_is_ready():
raise tf2.TimeoutException("The BufferServer is not ready")

event = threading.Event()

def unblock(future):
nonlocal event
event.set()

send_goal_future = self.action_client.send_goal_async(goal)
send_goal_future.add_done_callback(unblock)

def unblock_by_timeout():
nonlocal send_goal_future, goal, event
clock = Clock()
Expand All @@ -184,13 +184,13 @@ def unblock_by_timeout():
while not send_goal_future.done() and not event.is_set():
if clock.now() > start_time + timeout + timeout_padding:
break
# TODO(vinnamkim): rclpy.Rate is not ready
# TODO(vinnamkim): rclpy.Rate is not ready
# See https://github.com/ros2/rclpy/issues/186
#r = rospy.Rate(self.check_frequency)
sleep(1.0 / self.check_frequency)

event.set()

t = threading.Thread(target=unblock_by_timeout)
t.start()

Expand All @@ -204,7 +204,7 @@ def unblock_by_timeout():
raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server")

goal_handle = send_goal_future.result()

if not goal_handle.accepted:
raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back with accepted status. Something is likely wrong with the server.")

Expand Down

0 comments on commit ae6689e

Please sign in to comment.