Skip to content

Commit

Permalink
Lint
Browse files Browse the repository at this point in the history
  • Loading branch information
jacobperron committed Jan 24, 2019
1 parent 65db2df commit e6a272d
Show file tree
Hide file tree
Showing 6 changed files with 35 additions and 18 deletions.
3 changes: 2 additions & 1 deletion rclpy/rclpy/action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,8 @@ def __init__(
feedback_sub_qos_profile=qos_profile_default,
status_sub_qos_profile=qos_profile_action_status_default
):
"""Constructor.
"""
Constructor.
:param node: The ROS node to add the action client to.
:param action_type: Type of the action.
Expand Down
2 changes: 1 addition & 1 deletion rclpy/rclpy/qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

from enum import IntEnum

from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.impl.implementation_singleton import rclpy_action_implementation as _rclpy_action
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy


class QoSProfile:
Expand Down
4 changes: 2 additions & 2 deletions rclpy/src/rclpy/_rclpy.c
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@

#include <Python.h>

#include "./impl/common.h"

#include <rcl/error_handling.h>
#include <rcl/expand_topic_name.h>
#include <rcl/graph.h>
Expand All @@ -40,6 +38,8 @@

#include <signal.h>

#include "./impl/common.h"

static rcl_guard_condition_t * g_sigint_gc_handle;

#ifdef _WIN32
Expand Down
20 changes: 10 additions & 10 deletions rclpy/src/rclpy/_rclpy_action.c
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

// TODO: Review/complete documentation
// TODO(jacobperron): Review/complete documentation

#include <Python.h>

#include "./impl/common.h"

#include <rcl/error_handling.h>
#include <rcl_action/rcl_action.h>

#include "./impl/common.h"

typedef void * create_ros_message_signature (void);
typedef void destroy_ros_message_signature (void *);
typedef bool convert_from_py_signature (PyObject *, void *);
Expand Down Expand Up @@ -353,7 +353,7 @@ rclpy_action_wait_set_is_ready(PyObject * Py_UNUSED(self), PyObject * args)
if (PyCapsule_IsValid(py ## Profile, "rmw_qos_profile_t")) { \
void * p = PyCapsule_GetPointer(py ## Profile, "rmw_qos_profile_t"); \
rmw_qos_profile_t * qos_profile = (rmw_qos_profile_t *)p; \
Options.Profile = *qos_profile; \
Options.Profile = * qos_profile; \
PyMem_Free(p); \
if (PyCapsule_SetPointer(py ## Profile, Py_None)) { \
/* exception set by PyCapsule_SetPointer */ \
Expand Down Expand Up @@ -497,8 +497,8 @@ rclpy_action_server_is_available(PyObject * Py_UNUSED(self), PyObject * args)
bool is_available = false;
rcl_ret_t ret = rcl_action_server_is_available(node, action_client, &is_available);
if (RCL_RET_OK != ret) {
PyErr_Format(PyExc_RuntimeError,
"Failed to check if action server is available: %s", rcl_get_error_string().str);
PyErr_Format(PyExc_RuntimeError,
"Failed to check if action server is available: %s", rcl_get_error_string().str);
}

if (is_available) {
Expand All @@ -510,7 +510,7 @@ rclpy_action_server_is_available(PyObject * Py_UNUSED(self), PyObject * args)
#define SEND_SERVICE_REQUEST(Type) \
PyObject * pyaction_client; \
PyObject * pyrequest; \
if (!PyArg_ParseTuple(args, "OO", &pyaction_client, &pyrequest)) { \
if (!PyArg_ParseTuple(args, "OO", & pyaction_client, & pyrequest)) { \
return NULL; \
} \
rcl_action_client_t * action_client = (rcl_action_client_t *)PyCapsule_GetPointer( \
Expand Down Expand Up @@ -546,7 +546,7 @@ rclpy_action_server_is_available(PyObject * Py_UNUSED(self), PyObject * args)
} \
int64_t sequence_number; \
rcl_ret_t ret = rcl_action_send_ ## Type ## _request( \
action_client, raw_ros_request, &sequence_number); \
action_client, raw_ros_request, & sequence_number); \
destroy_ros_message(raw_ros_request); \
if (ret != RCL_RET_OK) { \
PyErr_Format(PyExc_RuntimeError, \
Expand All @@ -559,7 +559,7 @@ rclpy_action_server_is_available(PyObject * Py_UNUSED(self), PyObject * args)
#define TAKE_SERVICE_RESPONSE(Type) \
PyObject * pyaction_client; \
PyObject * pyresponse_type; \
if (!PyArg_ParseTuple(args, "OO", &pyaction_client, &pyresponse_type)) { \
if (!PyArg_ParseTuple(args, "OO", & pyaction_client, & pyresponse_type)) { \
return NULL; \
} \
rcl_action_client_t * action_client = (rcl_action_client_t *)PyCapsule_GetPointer( \
Expand Down Expand Up @@ -721,7 +721,7 @@ rclpy_action_take_cancel_response(PyObject * Py_UNUSED(self), PyObject * args)
#define TAKE_MESSAGE(Type) \
PyObject * pyaction_client; \
PyObject * pymsg_type; \
if (!PyArg_ParseTuple(args, "OO", &pyaction_client, &pymsg_type)) { \
if (!PyArg_ParseTuple(args, "OO", & pyaction_client, & pymsg_type)) { \
return NULL; \
} \
rcl_action_client_t * action_client = (rcl_action_client_t *)PyCapsule_GetPointer( \
Expand Down
19 changes: 16 additions & 3 deletions rclpy/src/rclpy/impl/common.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,18 @@
#ifndef RCLPY_IMPL_COMMON_H_
#define RCLPY_IMPL_COMMON_H_
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLPY__IMPL__COMMON_H_
#define RCLPY__IMPL__COMMON_H_

#include <Python.h>

Expand Down Expand Up @@ -44,4 +57,4 @@ get_capsule_pointer(PyObject * pymetaclass, const char * attr)
Py_DECREF(pyattr);
return ptr;
}
#endif // RCLPY_IMPL_COMMON_H_
#endif // RCLPY__IMPL__COMMON_H_
5 changes: 4 additions & 1 deletion rclpy/test/test_action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,9 @@ def test_send_cancel_async(self):
cancel_future = ac.cancel_goal_async(goal_handle)
rclpy.spin_until_future_complete(self.node, cancel_future, self.executor)
self.assertTrue(cancel_future.done())
self.assertEqual(cancel_future.result().goals_canceling[0].goal_id, goal_handle.goal_id)
self.assertEqual(
cancel_future.result().goals_canceling[0].goal_id,
goal_handle.goal_id)
finally:
ac.destroy()

Expand All @@ -297,5 +299,6 @@ def test_get_result_async(self):
finally:
ac.destroy()


if __name__ == '__main__':
unittest.main()

0 comments on commit e6a272d

Please sign in to comment.