├── .gitignore
├── actionlib_tools
├── src
│ └── actionlib_tools
│ │ ├── __init__.py
│ │ ├── dynamic_action.py
│ │ └── library.py
├── setup.py
├── CMakeLists.txt
├── package.xml
└── CHANGELOG.rst
├── actionlib
├── action
│ ├── TwoInts.action
│ ├── Test.action
│ └── TestRequest.action
├── test
│ ├── test_imports.launch
│ ├── test_python_server_components.launch
│ ├── test_cpp_simple_client_allocator.launch
│ ├── test_cpp_action_client_destruction.launch
│ ├── test_server_goal_handle_destruction.launch
│ ├── test_cpp_simple_client_cancel_crash.launch
│ ├── ref_server_test.launch
│ ├── test_python_server.launch
│ ├── test_python_server2.launch
│ ├── test_python_server3.launch
│ ├── test_python_simple_server.launch
│ ├── test_python_simple_client.launch
│ ├── test_python_exercise_simple_client.launch
│ ├── test_cpp_exercise_simple_client.launch
│ ├── simple_execute_ref_server_test.launch
│ ├── test_simple_action_server_deadlock_python.launch
│ ├── simple_client_allocator_test.cpp
│ ├── test_imports.py
│ ├── action_client_destruction_test.cpp
│ ├── add_two_ints_client.cpp
│ ├── test_cpp_simple_client_cancel_crash.cpp
│ ├── add_two_ints_server.cpp
│ ├── simple_python_client_test.py
│ ├── simple_action_server_deadlock_companion.py
│ ├── simple_client_wait_test.cpp
│ ├── ref_simple_server.py
│ ├── ref_server.cpp
│ ├── test_ref_simple_action_server.py
│ ├── simple_execute_ref_server.cpp
│ ├── simple_action_server_construction_test.cpp
│ ├── CMakeLists.txt
│ ├── ref_server.py
│ ├── destruction_guard_test.cpp
│ ├── test_server_components.py
│ ├── server_goal_handle_destruction.cpp
│ ├── mock_simple_server.py
│ ├── test_simple_action_server_deadlock.py
│ ├── simple_client_test.cpp
│ ├── exercise_simple_client.cpp
│ └── exercise_simple_client.py
├── setup.py
├── CMakeLists.txt
├── package.xml
├── mainpage.dox
├── src
│ ├── actionlib
│ │ ├── exceptions.py
│ │ ├── __init__.py
│ │ ├── handle_tracker_deleter.py
│ │ ├── goal_id_generator.py
│ │ └── status_tracker.py
│ └── goal_id_generator.cpp
└── include
│ └── actionlib
│ ├── decl.h
│ ├── goal_id_generator.h
│ ├── server
│ ├── handle_tracker_deleter_imp.h
│ ├── status_tracker_imp.h
│ ├── status_tracker.h
│ ├── handle_tracker_deleter.h
│ ├── service_server_imp.h
│ ├── service_server.h
│ └── action_server.h
│ ├── one_shot_timer.h
│ ├── enclosure_deleter.h
│ ├── action_definition.h
│ ├── client
│ ├── simple_goal_state.h
│ ├── connection_monitor.h
│ ├── terminal_state.h
│ ├── service_client.h
│ ├── comm_state.h
│ ├── simple_client_goal_state.h
│ ├── service_client_imp.h
│ └── goal_manager_imp.h
│ └── destruction_guard.h
└── README.md
/.gitignore:
--------------------------------------------------------------------------------
1 | *.pyc
2 |
--------------------------------------------------------------------------------
/actionlib_tools/src/actionlib_tools/__init__.py:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/actionlib/action/TwoInts.action:
--------------------------------------------------------------------------------
1 | int64 a
2 | int64 b
3 | ---
4 | int64 sum
5 | ---
6 |
--------------------------------------------------------------------------------
/actionlib/action/Test.action:
--------------------------------------------------------------------------------
1 | int32 goal
2 | ---
3 | int32 result
4 | ---
5 | int32 feedback
6 |
--------------------------------------------------------------------------------
/actionlib/test/test_imports.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_server_components.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/actionlib/test/test_cpp_simple_client_allocator.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/actionlib/test/test_cpp_action_client_destruction.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/actionlib/test/test_server_goal_handle_destruction.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/actionlib/test/test_cpp_simple_client_cancel_crash.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Archived - ROS 1 End-of-life
2 |
3 | This repository contains ROS 1 packages.
4 | The last supported ROS 1 release, ROS Noetic, [officially reached end of life on May 31st, 2025](https://bit.ly/NoeticEOL).
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/test/ref_server_test.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_server.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_server2.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_server3.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | from setuptools import setup
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 | d = generate_distutils_setup(
7 | packages=['actionlib'],
8 | package_dir={'': 'src'}
9 | )
10 |
11 | setup(**d)
12 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_simple_server.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_simple_client.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/actionlib_tools/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 |
3 | from setuptools import setup
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 | d = generate_distutils_setup(
7 | packages=['actionlib_tools'],
8 | package_dir={'': 'src'}
9 | )
10 |
11 | setup(**d)
12 |
--------------------------------------------------------------------------------
/actionlib/test/test_python_exercise_simple_client.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
5 |
6 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/actionlib/test/test_cpp_exercise_simple_client.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
5 |
6 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/actionlib_tools/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(actionlib_tools)
3 |
4 | find_package(catkin REQUIRED)
5 |
6 | catkin_python_setup()
7 |
8 | catkin_package()
9 |
10 | catkin_install_python(PROGRAMS
11 | scripts/axclient.py
12 | scripts/axserver.py
13 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
14 |
--------------------------------------------------------------------------------
/actionlib/test/simple_execute_ref_server_test.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/actionlib/action/TestRequest.action:
--------------------------------------------------------------------------------
1 | int32 TERMINATE_SUCCESS = 0
2 | int32 TERMINATE_ABORTED = 1
3 | int32 TERMINATE_REJECTED = 2
4 | int32 TERMINATE_LOSE = 3
5 | int32 TERMINATE_DROP = 4
6 | int32 TERMINATE_EXCEPTION = 5
7 | int32 terminate_status
8 | bool ignore_cancel # If true, ignores requests to cancel
9 | string result_text
10 | int32 the_result # Desired value for the_result in the Result
11 | bool is_simple_client
12 | duration delay_accept # Delays accepting the goal by this amount of time
13 | duration delay_terminate # Delays terminating for this amount of time
14 | duration pause_status # Pauses the status messages for this amount of time
15 | ---
16 | int32 the_result
17 | bool is_simple_server
18 | ---
19 |
--------------------------------------------------------------------------------
/actionlib/test/test_simple_action_server_deadlock_python.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/actionlib_tools/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | actionlib_tools
4 | 1.14.3
5 | The actionlib_tools package
6 |
7 | Michael Carroll
8 | Jacob Perron
9 | BSD
10 |
11 | http://www.ros.org/wiki/actionlib
12 | https://github.com/ros/actionlib/issues
13 | https://github.com/ros/actionlib
14 | Eitan Marder-Eppstein
15 | Vijay Pradeep
16 | Mikael Arguedas
17 |
18 | catkin
19 |
20 | rospy
21 | rostopic
22 | roslib
23 | actionlib
24 | actionlib_msgs
25 |
26 | python3-wxgtk4.0
27 |
28 |
29 |
--------------------------------------------------------------------------------
/actionlib/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(actionlib)
3 |
4 | find_package(catkin REQUIRED COMPONENTS actionlib_msgs message_generation roscpp std_msgs)
5 | find_package(Boost REQUIRED COMPONENTS thread)
6 |
7 | include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
8 | link_directories(${catkin_LIBRARY_DIRS})
9 |
10 | catkin_python_setup()
11 |
12 | add_action_files(DIRECTORY action FILES Test.action TestRequest.action TwoInts.action)
13 | generate_messages(DEPENDENCIES actionlib_msgs std_msgs)
14 |
15 | catkin_package(
16 | INCLUDE_DIRS include
17 | LIBRARIES actionlib
18 | CATKIN_DEPENDS actionlib_msgs message_runtime roscpp std_msgs
19 | DEPENDS Boost
20 | )
21 |
22 | add_library(actionlib src/connection_monitor.cpp src/goal_id_generator.cpp)
23 | target_link_libraries(actionlib ${catkin_LIBRARIES} ${Boost_LIBRARIES})
24 | add_dependencies(actionlib actionlib_gencpp)
25 |
26 | install(TARGETS ${PROJECT_NAME}
27 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
28 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
29 | RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
30 | install(DIRECTORY include/${PROJECT_NAME}/
31 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
32 | FILES_MATCHING PATTERN "*.h")
33 |
34 | if(CATKIN_ENABLE_TESTING)
35 | find_package(rostest)
36 | add_subdirectory(test)
37 | endif()
38 |
--------------------------------------------------------------------------------
/actionlib/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | actionlib
5 | 1.14.3
6 |
7 | The actionlib stack provides a standardized interface for
8 | interfacing with preemptable tasks. Examples of this include moving
9 | the base to a target location, performing a laser scan and returning
10 | the resulting point cloud, detecting the handle of a door, etc.
11 |
12 | Michael Carroll
13 | Jacob Perron
14 | BSD
15 |
16 | http://www.ros.org/wiki/actionlib
17 | https://github.com/ros/actionlib/issues
18 | https://github.com/ros/actionlib
19 | Eitan Marder-Eppstein
20 | Vijay Pradeep
21 | Mikael Arguedas
22 |
23 | catkin
24 |
25 | message_generation
26 |
27 | actionlib_msgs
28 | libboost-dev
29 | libboost-thread-dev
30 | roscpp
31 | rospy
32 | rostest
33 | std_msgs
34 |
35 | message_runtime
36 |
37 | rosnode
38 | rosunit
39 |
40 |
--------------------------------------------------------------------------------
/actionlib/mainpage.dox:
--------------------------------------------------------------------------------
1 | /**
2 | \mainpage
3 | \htmlinclude manifest.html
4 |
5 | \section ActionClientAPI ActionClient Code API
6 | - \link actionlib::SimpleActionClient SimpleActionClient (C++) \endlink
7 | - \link actionlib::simple_action_client::SimpleActionClient SimpleActionClient (Python) \endlink
8 |
9 | \section ActionServerAPI ActionServer Code API
10 | - actionlib::SimpleActionServer
11 | - \link actionlib::simple_action_server::SimpleActionServer SimpleActionServer (Python) \endlink
12 |
13 | \section protocol Communication Protocol
14 | The values for the status of a goal are as follows:
15 | - \b PENDING - The goal has yet to be processed by the action server
16 | - \b ACTIVE - The goal is currently being processed by the action server
17 | - \b REJECTED - The goal was rejected by the action server without being processed and without a request from the action client to cancel
18 | - \b SUCCEEDED - The goal was achieved successfully by the action server
19 | - \b ABORTED - The goal was aborted by the action server
20 | - \b PREEMPTING - Processing of the goal was canceled by either another goal, or a cancel request sent to the action server
21 | - \b PREEMPTED - The goal was preempted by either another goal, or a preempt message being sent to the action server
22 | - \b RECALLING - The goal has not been processed and a cancel request has been received from the action client, but the action server has not confirmed the goal is canceled
23 | - \b RECALLED - The goal was canceled by either another goal, or a cancel request before the action server began processing the goal
24 | - \b LOST - The goal was sent by the ActionClient, but disappeared due to some communication error
25 |
26 | */
27 |
--------------------------------------------------------------------------------
/actionlib/src/actionlib/exceptions.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2010, Willow Garage, Inc.
2 | # All rights reserved.
3 | #
4 | # Redistribution and use in source and binary forms, with or without
5 | # modification, are permitted provided that the following conditions are met:
6 | #
7 | # * Redistributions of source code must retain the above copyright
8 | # notice, this list of conditions and the following disclaimer.
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | # * Neither the name of the Willow Garage, Inc. nor the names of its
13 | # contributors may be used to endorse or promote products derived from
14 | # this software without specific prior written permission.
15 | #
16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 | # POSSIBILITY OF SUCH DAMAGE.
27 |
28 | # Author: Jonathan Bohren
29 |
30 |
31 | class ActionException(Exception):
32 | pass
33 |
--------------------------------------------------------------------------------
/actionlib/src/actionlib/__init__.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2009, Willow Garage, Inc.
2 | # All rights reserved.
3 | #
4 | # Redistribution and use in source and binary forms, with or without
5 | # modification, are permitted provided that the following conditions are met:
6 | #
7 | # * Redistributions of source code must retain the above copyright
8 | # notice, this list of conditions and the following disclaimer.
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | # * Neither the name of the Willow Garage, Inc. nor the names of its
13 | # contributors may be used to endorse or promote products derived from
14 | # this software without specific prior written permission.
15 | #
16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 | # POSSIBILITY OF SUCH DAMAGE.
27 |
28 | from actionlib.action_client import *
29 | from actionlib.simple_action_client import *
30 | from actionlib.action_server import *
31 | from actionlib.simple_action_server import *
32 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/decl.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2009, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of the Willow Garage nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | *********************************************************************/
36 | /*
37 | * Cross platform macros.
38 | *
39 | */
40 | #ifndef ACTIONLIB__DECL_H_
41 | #define ACTIONLIB__DECL_H_
42 |
43 | #include
44 |
45 | #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
46 | #ifdef actionlib_EXPORTS // we are building a shared lib/dll
47 | #define ACTIONLIB_DECL ROS_HELPER_EXPORT
48 | #else // we are using shared lib/dll
49 | #define ACTIONLIB_DECL ROS_HELPER_IMPORT
50 | #endif
51 | #else // ros is being built around static libraries
52 | #define ACTIONLIB_DECL
53 | #endif
54 |
55 | #endif // ACTIONLIB__DECL_H_
56 |
--------------------------------------------------------------------------------
/actionlib/src/actionlib/handle_tracker_deleter.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2009, Willow Garage, Inc.
2 | # All rights reserved.
3 | #
4 | # Redistribution and use in source and binary forms, with or without
5 | # modification, are permitted provided that the following conditions are met:
6 | #
7 | # * Redistributions of source code must retain the above copyright
8 | # notice, this list of conditions and the following disclaimer.
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | # * Neither the name of the Willow Garage, Inc. nor the names of its
13 | # contributors may be used to endorse or promote products derived from
14 | # this software without specific prior written permission.
15 | #
16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 | # POSSIBILITY OF SUCH DAMAGE.
27 |
28 | # Author: Alexander Sorokin.
29 | # Based on C++ goal_id_generator.h/cpp
30 | import rospy
31 |
32 |
33 | class HandleTrackerDeleter:
34 | """
35 | * @class HandleTrackerDeleter
36 | * @brief A class to help with tracking GoalHandles and removing goals
37 | * from the status list when the last GoalHandle associated with a given
38 | * goal is deleted.
39 | """
40 |
41 | def __init__(self, action_server, status_tracker):
42 | """
43 | @brief create deleter
44 | """
45 | self.action_server = action_server
46 | self.status_tracker = status_tracker
47 |
48 | def __call__(self, ptr):
49 | if self.action_server:
50 | with self.action_server.lock:
51 | self.status_tracker.handle_destruction_time = rospy.Time.now()
52 |
--------------------------------------------------------------------------------
/actionlib/test/simple_client_allocator_test.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | //! \author Vijay Pradeep
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 |
42 | using namespace actionlib;
43 |
44 | TEST(SimpleClientAllocator, easy_test) {
45 | typedef actionlib::SimpleActionClient TrajClient;
46 |
47 | TrajClient * traj_client_ = new TrajClient("test_action", true);
48 |
49 | ros::Duration(1, 0).sleep();
50 |
51 | delete traj_client_;
52 | }
53 |
54 | int main(int argc, char ** argv)
55 | {
56 | testing::InitGoogleTest(&argc, argv);
57 |
58 | ros::init(argc, argv, "simple_client_allocator");
59 |
60 | return RUN_ALL_TESTS();
61 | }
62 |
--------------------------------------------------------------------------------
/actionlib/test/test_imports.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # Copyright (c) 2009, Willow Garage, Inc.
3 | # All rights reserved.
4 | #
5 | # Redistribution and use in source and binary forms, with or without
6 | # modification, are permitted provided that the following conditions are met:
7 | #
8 | # * Redistributions of source code must retain the above copyright
9 | # notice, this list of conditions and the following disclaimer.
10 | # * Redistributions in binary form must reproduce the above copyright
11 | # notice, this list of conditions and the following disclaimer in the
12 | # documentation and/or other materials provided with the distribution.
13 | # * Neither the name of the Willow Garage, Inc. nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 | # Author: Alexander Sorokin.
30 |
31 |
32 | PKG = 'actionlib'
33 |
34 | import sys
35 | import unittest
36 |
37 |
38 | # A simple unit test to make sure python module structure and files aren't broken
39 | class TestImports(unittest.TestCase):
40 | # import everything
41 | def test_imports(self):
42 | from actionlib import simple_action_client
43 | from actionlib import action_client
44 |
45 | from actionlib import goal_id_generator
46 | from actionlib import handle_tracker_deleter
47 | from actionlib import server_goal_handle
48 | from actionlib import status_tracker
49 |
50 | from actionlib import action_server
51 | from actionlib import simple_action_server
52 |
53 | self.assertEqual(1, 1, "1!=1")
54 |
55 |
56 | if __name__ == '__main__':
57 | import rostest
58 | print(sys.path)
59 | rostest.rosrun(PKG, 'test_imports', TestImports)
60 |
--------------------------------------------------------------------------------
/actionlib_tools/src/actionlib_tools/dynamic_action.py:
--------------------------------------------------------------------------------
1 | # **********************************************************
2 | # Software License Agreement (BSD License)
3 | #
4 | # Copyright (c) 2009, Willow Garage, Inc.
5 | # All rights reserved.
6 | #
7 | # Redistribution and use in source and binary forms, with or without
8 | # modification, are permitted provided that the following conditions
9 | # are met:
10 | #
11 | # * Redistributions of source code must retain the above copyright
12 | # notice, this list of conditions and the following disclaimer.
13 | # * Redistributions in binary form must reproduce the above
14 | # copyright notice, this list of conditions and the following
15 | # disclaimer in the documentation and/or other materials provided
16 | # with the distribution.
17 | # * Neither the name of Willow Garage, Inc. nor the names of its
18 | # contributors may be used to endorse or promote products derived
19 | # from this software without specific prior written permission.
20 | #
21 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | # POSSIBILITY OF SUCH DAMAGE.
33 | #
34 | # Author: Eitan Marder-Eppstein
35 | # **********************************************************
36 | import roslib
37 | import rospy
38 | import sys
39 |
40 |
41 | class DynamicAction(object):
42 | def __init__(self, name):
43 | # remove "Action" string from name
44 | assert("Action" in name)
45 | self.name = name[0:len(name)-6]
46 | self.action = self.load_submsg('Action')
47 | self.goal = self.load_submsg('Goal')
48 | self.feedback = self.load_submsg('Feedback')
49 | self.result = self.load_submsg('Result')
50 |
51 | def load_submsg(self, subname):
52 | msgclass = roslib.message.get_message_class(self.name + subname)
53 | if msgclass is None:
54 | rospy.logfatal('Could not load message for: %s' % (self.name + subname))
55 | sys.exit(1)
56 | return msgclass
57 |
--------------------------------------------------------------------------------
/actionlib/test/action_client_destruction_test.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | //! \author Vijay Pradeep
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 |
42 | using namespace actionlib;
43 |
44 | TEST(ActionClientDestruction, persistent_goal_handles_1) {
45 | ActionClient * test_client = new ActionClient("test_action");
46 |
47 | ClientGoalHandle gh = test_client->sendGoal(TestGoal());
48 |
49 | ros::Duration(.1).sleep();
50 |
51 | printf("Destroying ActionClient\n");
52 | delete test_client;
53 | printf("Done Destroying ActionClient\n");
54 | }
55 |
56 | int main(int argc, char ** argv)
57 | {
58 | testing::InitGoogleTest(&argc, argv);
59 |
60 | ros::init(argc, argv, "simple_client_allocator");
61 |
62 | return RUN_ALL_TESTS();
63 | }
64 |
--------------------------------------------------------------------------------
/actionlib/test/add_two_ints_client.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2009, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #include
38 | #include
39 | #include
40 |
41 | int main(int argc, char ** argv)
42 | {
43 | ros::init(argc, argv, "add_two_ints_client");
44 | if (argc != 3) {
45 | ROS_INFO_NAMED("actionlib", "Usage: add_two_ints_client X Y");
46 | return 1;
47 | }
48 |
49 | ros::NodeHandle n;
50 | actionlib::ServiceClient client = actionlib::serviceClient(n,
51 | "add_two_ints");
52 | client.waitForServer();
53 | actionlib::TwoIntsGoal req;
54 | actionlib::TwoIntsResult resp;
55 |
56 | req.a = atoi(argv[1]);
57 | req.b = atoi(argv[2]);
58 |
59 | if (client.call(req, resp)) {
60 | ROS_INFO_NAMED("actionlib", "Sum: %ld", (int64_t)resp.sum);
61 | return 1;
62 | }
63 |
64 | return 0;
65 | }
66 |
--------------------------------------------------------------------------------
/actionlib/test/test_cpp_simple_client_cancel_crash.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | //! \author Vijay Pradeep
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 |
42 | typedef actionlib::SimpleActionClient Client;
43 |
44 | TEST(SimpleClientCancelCrash, uninitialized_crash) {
45 | ros::NodeHandle nh;
46 | Client client("test_client", true);
47 | ROS_INFO_NAMED("actionlib", "calling cancelGoal()");
48 | client.cancelGoal();
49 | ROS_INFO_NAMED("actionlib", "Done calling cancelGoal()");
50 | EXPECT_TRUE(true);
51 | ROS_INFO_NAMED("actionlib", "Successfully done with test. Exiting");
52 | }
53 |
54 | int main(int argc, char ** argv)
55 | {
56 | testing::InitGoogleTest(&argc, argv);
57 |
58 | ros::init(argc, argv, "test_cpp_simple_client_cancel_crash");
59 |
60 | return RUN_ALL_TESTS();
61 | }
62 |
--------------------------------------------------------------------------------
/actionlib/test/add_two_ints_server.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2009, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #include
38 | #include
39 | #include
40 |
41 | bool add(const actionlib::TwoIntsGoal & req, actionlib::TwoIntsResult & res)
42 | {
43 | res.sum = req.a + req.b;
44 | ROS_INFO_NAMED("actionlib", "request: x=%ld, y=%ld", (int64_t)req.a, (int64_t)req.b);
45 | ROS_INFO_NAMED("actionlib", " sending back response: [%ld]", (int64_t)res.sum);
46 | return true;
47 | }
48 |
49 | int main(int argc, char ** argv)
50 | {
51 | ros::init(argc, argv, "add_two_ints_server");
52 | ros::NodeHandle n;
53 |
54 | actionlib::ServiceServer service = actionlib::advertiseService(n,
55 | "add_two_ints",
56 | boost::bind(add, boost::placeholders::_1, boost::placeholders::_2));
57 |
58 | ros::spin();
59 |
60 | return 0;
61 | }
62 |
--------------------------------------------------------------------------------
/actionlib/src/goal_id_generator.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #include
36 | #include
37 | #include
38 | #include
39 |
40 | // using namespace actionlib;
41 |
42 | static boost::mutex s_goalcount_mutex_;
43 | static unsigned int s_goalcount_ = 0;
44 |
45 | actionlib::GoalIDGenerator::GoalIDGenerator()
46 | {
47 | setName(ros::this_node::getName());
48 | }
49 |
50 | actionlib::GoalIDGenerator::GoalIDGenerator(const std::string & name)
51 | {
52 | setName(name);
53 | }
54 |
55 | void actionlib::GoalIDGenerator::setName(const std::string & name)
56 | {
57 | name_ = name;
58 | }
59 |
60 | actionlib_msgs::GoalID actionlib::GoalIDGenerator::generateID()
61 | {
62 | actionlib_msgs::GoalID id;
63 | ros::Time cur_time = ros::Time::now();
64 | std::stringstream ss;
65 |
66 | ss << name_ << "-";
67 |
68 | {
69 | boost::mutex::scoped_lock lock(s_goalcount_mutex_);
70 | s_goalcount_++;
71 | ss << s_goalcount_ << "-";
72 | }
73 |
74 | ss << cur_time.sec << "." << cur_time.nsec;
75 | id.id = ss.str();
76 | id.stamp = cur_time;
77 | return id;
78 | }
79 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/goal_id_generator.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #ifndef ACTIONLIB__GOAL_ID_GENERATOR_H_
36 | #define ACTIONLIB__GOAL_ID_GENERATOR_H_
37 |
38 | #include
39 |
40 | #include
41 | #include
42 |
43 | #include "ros/time.h"
44 | #include "actionlib_msgs/GoalID.h"
45 |
46 | namespace actionlib
47 | {
48 |
49 | class ACTIONLIB_DECL GoalIDGenerator
50 | {
51 | public:
52 | /**
53 | * Create a generator that prepends the fully qualified node name to the Goal ID
54 | */
55 | GoalIDGenerator();
56 |
57 | /**
58 | * \param name Unique name to prepend to the goal id. This will
59 | * generally be a fully qualified node name.
60 | */
61 | GoalIDGenerator(const std::string & name);
62 |
63 | /**
64 | * \param name Set the name to prepend to the goal id. This will
65 | * generally be a fully qualified node name.
66 | */
67 | void setName(const std::string & name);
68 |
69 | /**
70 | * \brief Generates a unique ID
71 | * \return A unique GoalID for this action
72 | */
73 | actionlib_msgs::GoalID generateID();
74 |
75 | private:
76 | std::string name_;
77 | };
78 |
79 | } // namespace actionlib
80 |
81 | #endif // ACTIONLIB__GOAL_ID_GENERATOR_H_
82 |
--------------------------------------------------------------------------------
/actionlib/test/simple_python_client_test.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | # Copyright (c) 2009, Willow Garage, Inc.
3 | # All rights reserved.
4 | #
5 | # Redistribution and use in source and binary forms, with or without
6 | # modification, are permitted provided that the following conditions are met:
7 | #
8 | # * Redistributions of source code must retain the above copyright
9 | # notice, this list of conditions and the following disclaimer.
10 | # * Redistributions in binary form must reproduce the above copyright
11 | # notice, this list of conditions and the following disclaimer in the
12 | # documentation and/or other materials provided with the distribution.
13 | # * Neither the name of the Willow Garage, Inc. nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 | import unittest
30 | import rospy
31 | from actionlib_msgs.msg import GoalStatus
32 | from actionlib import SimpleActionClient
33 | from actionlib.msg import TestAction, TestGoal
34 |
35 |
36 | class TestSimpleActionClient(unittest.TestCase):
37 |
38 | def testsimple(self):
39 | client = SimpleActionClient('reference_action', TestAction)
40 | self.assertTrue(client.wait_for_server(rospy.Duration(10.0)),
41 | 'Could not connect to the action server')
42 |
43 | goal = TestGoal(1)
44 | client.send_goal(goal)
45 | self.assertTrue(client.wait_for_result(rospy.Duration(10.0)),
46 | "Goal didn't finish")
47 | self.assertEqual(GoalStatus.SUCCEEDED, client.get_state())
48 | self.assertEqual("The ref server has succeeded", client.get_goal_status_text())
49 |
50 | goal = TestGoal(2)
51 | client.send_goal(goal)
52 | self.assertTrue(client.wait_for_result(rospy.Duration(10.0)),
53 | "Goal didn't finish")
54 | self.assertEqual(GoalStatus.ABORTED, client.get_state())
55 | self.assertEqual("The ref server has aborted", client.get_goal_status_text())
56 |
57 |
58 | if __name__ == '__main__':
59 | import rostest
60 | rospy.init_node('simple_python_client_test')
61 | rostest.rosrun('actionlib', 'test_simple_action_client_python', TestSimpleActionClient)
62 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/handle_tracker_deleter_imp.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_IMP_H_
38 | #define ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_IMP_H_
39 |
40 | #include
41 |
42 | namespace actionlib
43 | {
44 | template
45 | HandleTrackerDeleter::HandleTrackerDeleter(ActionServerBase * as,
46 | typename std::list >::iterator status_it,
47 | boost::shared_ptr guard)
48 | : as_(as), status_it_(status_it), guard_(guard) {}
49 |
50 | template
51 | void HandleTrackerDeleter::operator()(void *)
52 | {
53 | if (as_) {
54 | // make sure that the action server hasn't been destroyed yet
55 | DestructionGuard::ScopedProtector protector(*guard_);
56 | if (protector.isProtected()) {
57 | // make sure to lock while we erase status for this goal from the list
58 | boost::recursive_mutex::scoped_lock lock(as_->lock_);
59 | (*status_it_).handle_destruction_time_ = ros::Time::now();
60 | // as_->status_list_.erase(status_it_);
61 | }
62 | }
63 | }
64 | } // namespace actionlib
65 | #endif // ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_IMP_H_
66 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/status_tracker_imp.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__STATUS_TRACKER_IMP_H_
38 | #define ACTIONLIB__SERVER__STATUS_TRACKER_IMP_H_
39 | namespace actionlib
40 | {
41 | template
42 | StatusTracker::StatusTracker(const actionlib_msgs::GoalID & goal_id,
43 | unsigned int status)
44 | {
45 | // set the goal id and status appropriately
46 | status_.goal_id = goal_id;
47 | status_.status = status;
48 | }
49 |
50 | template
51 | StatusTracker::StatusTracker(const boost::shared_ptr & goal)
52 | : goal_(goal)
53 | {
54 | // set the goal_id from the message
55 | status_.goal_id = goal_->goal_id;
56 |
57 | // initialize the status of the goal to pending
58 | status_.status = actionlib_msgs::GoalStatus::PENDING;
59 |
60 | // if the goal id is zero, then we need to make up an id for the goal
61 | if (status_.goal_id.id == "") {
62 | status_.goal_id = id_generator_.generateID();
63 | }
64 |
65 | // if the timestamp of the goal is zero, then we'll set it to now()
66 | if (status_.goal_id.stamp == ros::Time()) {
67 | status_.goal_id.stamp = ros::Time::now();
68 | }
69 | }
70 | } // namespace actionlib
71 | #endif // ACTIONLIB__SERVER__STATUS_TRACKER_IMP_H_
72 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/status_tracker.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__STATUS_TRACKER_H_
38 | #define ACTIONLIB__SERVER__STATUS_TRACKER_H_
39 |
40 | #include
41 | #include
42 | #include
43 |
44 | #include
45 |
46 | namespace actionlib
47 | {
48 |
49 | /**
50 | * @class StatusTracker
51 | * @brief A class for storing the status of each goal the action server
52 | * is currently working on
53 | */
54 | template
55 | class StatusTracker
56 | {
57 | private:
58 | // generates typedefs that we'll use to make our lives easier
59 | ACTION_DEFINITION(ActionSpec)
60 |
61 | public:
62 | StatusTracker(const actionlib_msgs::GoalID & goal_id, unsigned int status);
63 |
64 | StatusTracker(const boost::shared_ptr & goal);
65 |
66 | boost::shared_ptr goal_;
67 | boost::weak_ptr handle_tracker_;
68 | actionlib_msgs::GoalStatus status_;
69 | ros::Time handle_destruction_time_;
70 |
71 | private:
72 | GoalIDGenerator id_generator_;
73 | };
74 | } // namespace actionlib
75 |
76 | // include the implementation
77 | #include
78 | #endif // ACTIONLIB__SERVER__STATUS_TRACKER_H_
79 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/one_shot_timer.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #ifndef ACTIONLIB__ONE_SHOT_TIMER_H_
36 | #define ACTIONLIB__ONE_SHOT_TIMER_H_
37 |
38 | #include "ros/ros.h"
39 | #include "boost/bind/bind.hpp"
40 |
41 | //! Horrible hack until ROS Supports this (ROS Trac #1387)
42 | class OneShotTimer
43 | {
44 | public:
45 | OneShotTimer()
46 | : active_(false) {}
47 |
48 | void cb(const ros::TimerEvent & e)
49 | {
50 | if (active_) {
51 | active_ = false;
52 |
53 | if (callback_) {
54 | callback_(e);
55 | } else {
56 | ROS_ERROR_NAMED("actionlib", "Got a nullptr Timer OneShotTimer Callback");
57 | }
58 | }
59 | }
60 |
61 | boost::function getCb()
62 | {
63 | return boost::bind(&OneShotTimer::cb, this, boost::placeholders::_1);
64 | }
65 |
66 | void registerOneShotCb(boost::function callback)
67 | {
68 | callback_ = callback;
69 | }
70 |
71 | void stop()
72 | {
73 | // timer_.stop();
74 | active_ = false;
75 | }
76 |
77 | const ros::Timer & operator=(const ros::Timer & rhs)
78 | {
79 | active_ = true;
80 | timer_ = rhs;
81 | return timer_;
82 | }
83 |
84 | private:
85 | ros::Timer timer_;
86 | bool active_;
87 | boost::function callback_;
88 | };
89 |
90 |
91 | #endif // ACTIONLIB__ONE_SHOT_TIMER_H_
92 |
--------------------------------------------------------------------------------
/actionlib/src/actionlib/goal_id_generator.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2009, Willow Garage, Inc.
2 | # All rights reserved.
3 | #
4 | # Redistribution and use in source and binary forms, with or without
5 | # modification, are permitted provided that the following conditions are met:
6 | #
7 | # * Redistributions of source code must retain the above copyright
8 | # notice, this list of conditions and the following disclaimer.
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | # * Neither the name of the Willow Garage, Inc. nor the names of its
13 | # contributors may be used to endorse or promote products derived from
14 | # this software without specific prior written permission.
15 | #
16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 | # POSSIBILITY OF SUCH DAMAGE.
27 |
28 | # Author: Alexander Sorokin.
29 | # Based on C++ goal_id_generator.h/cpp
30 | import rospy
31 |
32 | from actionlib_msgs.msg import GoalID
33 | import threading
34 |
35 | global s_goalcount_lock
36 | global s_goalcount
37 | s_goalcount_lock = threading.Lock()
38 | s_goalcount = 0
39 |
40 |
41 | class GoalIDGenerator:
42 |
43 | def __init__(self, name=None):
44 | """
45 | * Create a generator that prepends the fully qualified node name to the Goal ID
46 | * \param name Unique name to prepend to the goal id. This will
47 | * generally be a fully qualified node name.
48 | """
49 | if name is not None:
50 | self.set_name(name)
51 | else:
52 | self.set_name(rospy.get_name())
53 |
54 | def set_name(self, name):
55 | """
56 | * \param name Set the name to prepend to the goal id. This will
57 | * generally be a fully qualified node name.
58 | """
59 | self.name = name
60 |
61 | def generate_ID(self):
62 | """
63 | * \brief Generates a unique ID
64 | * \return A unique GoalID for this action
65 | """
66 | id = GoalID()
67 | cur_time = rospy.Time.now()
68 | ss = self.name + "-"
69 | global s_goalcount_lock
70 | global s_goalcount
71 | with s_goalcount_lock:
72 | s_goalcount += 1
73 | ss += str(s_goalcount) + "-"
74 | ss += str(cur_time.secs) + "." + str(cur_time.nsecs)
75 |
76 | id.id = ss
77 | id.stamp = cur_time
78 | return id
79 |
--------------------------------------------------------------------------------
/actionlib/test/simple_action_server_deadlock_companion.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | #
3 | # Copyright (c) 2013, Miguel Sarabia
4 | # Imperial College London
5 | # All rights reserved.
6 | #
7 | # Redistribution and use in source and binary forms, with or without
8 | # modification, are permitted provided that the following conditions are met:
9 | #
10 | # * Redistributions of source code must retain the above copyright
11 | # notice, this list of conditions and the following disclaimer.
12 | # * Redistributions in binary form must reproduce the above copyright
13 | # notice, this list of conditions and the following disclaimer in the
14 | # documentation and/or other materials provided with the distribution.
15 | # * Neither the name of Imperial College London nor the names of its
16 | # contributors may be used to endorse or promote products derived from
17 | # this software without specific prior written permission.
18 | #
19 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 | # POSSIBILITY OF SUCH DAMAGE.
30 | #
31 |
32 |
33 | class Constants:
34 | node = "simple_action_server_deadlock_companion"
35 | topic = "deadlock"
36 | max_action_duration = 3
37 |
38 |
39 | import random
40 |
41 | import actionlib
42 | from actionlib.msg import TestAction, TestGoal
43 | from actionlib_msgs.msg import GoalStatus
44 | import rospy
45 |
46 |
47 | class DeadlockCompanion:
48 |
49 | def __init__(self):
50 | # Seed random with fully resolved name of node and current time
51 | random.seed(rospy.get_name() + str(rospy.Time.now().to_sec()))
52 |
53 | # Create actionlib client
54 | self.action_client = actionlib.SimpleActionClient(
55 | Constants.topic,
56 | TestAction)
57 |
58 | def run(self):
59 | while not rospy.is_shutdown():
60 | # Send dummy goal
61 | self.action_client.send_goal(TestGoal())
62 |
63 | # Wait for a random amount of time
64 | action_duration = random.uniform(0, Constants.max_action_duration)
65 | self.action_client.wait_for_result(rospy.Duration(action_duration))
66 |
67 | state = self.action_client.get_state()
68 | if state == GoalStatus.ACTIVE or state == GoalStatus.PENDING:
69 | self.action_client.cancel_goal()
70 |
71 |
72 | if __name__ == '__main__':
73 | rospy.init_node(Constants.node)
74 | try:
75 | companion = DeadlockCompanion()
76 | companion.run()
77 | except (KeyboardInterrupt, SystemExit):
78 | raise
79 | except:
80 | pass
81 |
--------------------------------------------------------------------------------
/actionlib/src/actionlib/status_tracker.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2009, Willow Garage, Inc.
2 | # All rights reserved.
3 | #
4 | # Redistribution and use in source and binary forms, with or without
5 | # modification, are permitted provided that the following conditions are met:
6 | #
7 | # * Redistributions of source code must retain the above copyright
8 | # notice, this list of conditions and the following disclaimer.
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | # * Neither the name of the Willow Garage, Inc. nor the names of its
13 | # contributors may be used to endorse or promote products derived from
14 | # this software without specific prior written permission.
15 | #
16 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 | # POSSIBILITY OF SUCH DAMAGE.
27 |
28 | # Author: Alexander Sorokin.
29 | # Based on C++ goal_id_generator.h/cpp
30 | import rospy
31 |
32 | import actionlib_msgs.msg
33 | from actionlib import goal_id_generator
34 |
35 |
36 | class StatusTracker:
37 | """
38 | * @class StatusTracker
39 | * @brief A class for storing the status of each goal the action server
40 | * is currently working on
41 | """
42 |
43 | def __init__(self, goal_id=None, status=None, goal=None):
44 | """
45 | @brief create status tracker. Either pass goal_id and status OR goal
46 | """
47 | self.goal = None
48 | self.handle_tracker = None
49 | self.status = actionlib_msgs.msg.GoalStatus()
50 |
51 | self.handle_destruction_time = rospy.Time()
52 |
53 | self.id_generator = goal_id_generator.GoalIDGenerator()
54 |
55 | if goal_id:
56 | # set the goal id and status appropriately
57 | self.status.goal_id = goal_id
58 | self.status.status = status
59 | else:
60 | self.goal = goal
61 | self.status.goal_id = goal.goal_id
62 |
63 | # initialize the status of the goal to pending
64 | self.status.status = actionlib_msgs.msg.GoalStatus.PENDING
65 |
66 | # if the goal id is zero, then we need to make up an id for the goal
67 | if self.status.goal_id.id == "":
68 | self.status.goal_id = self.id_generator.generate_ID()
69 |
70 | # if the timestamp of the goal is zero, then we'll set it to now()
71 | if self.status.goal_id.stamp == rospy.Time():
72 | self.status.goal_id.stamp = rospy.Time.now()
73 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/enclosure_deleter.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 |
38 | #include
39 |
40 | #ifndef ACTIONLIB__ENCLOSURE_DELETER_H_
41 | #define ACTIONLIB__ENCLOSURE_DELETER_H_
42 |
43 | namespace actionlib
44 | {
45 |
46 | /*
47 | * This allows the creation of a shared pointer to a section
48 | * of an already reference counted structure. For example,
49 | * if in the following picture Enclosure is reference counted with
50 | * a boost::shared_ptr and you want to return a boost::shared_ptr
51 | * to the Member that is referenced counted along with Enclosure objects
52 | *
53 | * Enclosure --------------- <--- Already reference counted
54 | * -----Member <------- A member of enclosure objects, eg. Enclosure.Member
55 | */
56 | template
57 | class EnclosureDeleter
58 | {
59 | public:
60 | EnclosureDeleter(const boost::shared_ptr & enc_ptr)
61 | : enc_ptr_(enc_ptr) {}
62 |
63 | template
64 | void operator()(Member *)
65 | {
66 | enc_ptr_.reset();
67 | }
68 |
69 | private:
70 | boost::shared_ptr enc_ptr_;
71 | };
72 |
73 | template
74 | boost::shared_ptr share_member(boost::shared_ptr enclosure, Member & member)
75 | {
76 | EnclosureDeleter d(enclosure);
77 | boost::shared_ptr p(&member, d);
78 | return p;
79 | }
80 |
81 | } // namespace actionlib
82 |
83 | #endif // ACTIONLIB__ENCLOSURE_DELETER_H_
84 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/handle_tracker_deleter.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_H_
38 | #define ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_H_
39 |
40 | #include
41 | #include
42 | #include
43 | #include
44 | #include
45 |
46 | namespace actionlib
47 | {
48 | // we need to forward declare the ActionServerBase class
49 | template
50 | class ActionServerBase;
51 |
52 | /**
53 | * @class HandleTrackerDeleter
54 | * @brief A class to help with tracking GoalHandles and removing goals
55 | * from the status list when the last GoalHandle associated with a given
56 | * goal is deleted.
57 | */
58 | // class to help with tracking status objects
59 | template
60 | class HandleTrackerDeleter
61 | {
62 | public:
63 | HandleTrackerDeleter(ActionServerBase * as,
64 | typename std::list >::iterator status_it,
65 | boost::shared_ptr guard);
66 |
67 | void operator()(void * ptr);
68 |
69 | private:
70 | ActionServerBase * as_;
71 | typename std::list >::iterator status_it_;
72 | boost::shared_ptr guard_;
73 | };
74 |
75 | } // namespace actionlib
76 | #include
77 | #endif // ACTIONLIB__SERVER__HANDLE_TRACKER_DELETER_H_
78 |
--------------------------------------------------------------------------------
/actionlib/test/simple_client_wait_test.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | //! \author Vijay Pradeep
36 |
37 | #include
38 | #include
39 | #include
40 |
41 | using namespace actionlib;
42 |
43 | TEST(SimpleClient, easy_wait_test) {
44 | ros::NodeHandle n;
45 | SimpleActionClient client(n, "reference_action");
46 |
47 | bool started = client.waitForServer(ros::Duration(10.0));
48 | ASSERT_TRUE(started);
49 |
50 | TestGoal goal;
51 | SimpleClientGoalState state(SimpleClientGoalState::LOST);
52 |
53 | goal.goal = 1;
54 | state = client.sendGoalAndWait(goal, ros::Duration(10, 0), ros::Duration(10, 0));
55 | EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED) <<
56 | "Expected [SUCCEEDED], but goal state is [" << client.getState().toString() << "]";
57 |
58 | goal.goal = 4;
59 | state = client.sendGoalAndWait(goal, ros::Duration(2, 0), ros::Duration(1, 0));
60 | EXPECT_TRUE(state == SimpleClientGoalState::PREEMPTED) <<
61 | "Expected [PREEMPTED], but goal state is [" << client.getState().toString() << "]";
62 | }
63 |
64 | void spinThread()
65 | {
66 | ros::NodeHandle nh;
67 | ros::spin();
68 | }
69 |
70 | int main(int argc, char ** argv)
71 | {
72 | testing::InitGoogleTest(&argc, argv);
73 |
74 | ros::init(argc, argv, "simple_client_test");
75 |
76 | boost::thread spin_thread(&spinThread);
77 |
78 | int result = RUN_ALL_TESTS();
79 |
80 | ros::shutdown();
81 |
82 | spin_thread.join();
83 |
84 | return result;
85 | }
86 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/action_definition.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2008, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__ACTION_DEFINITION_H_
38 | #define ACTIONLIB__ACTION_DEFINITION_H_
39 | // A macro that will generate helpful typedefs for action client, server, and policy implementers
40 | namespace actionlib
41 | {
42 | #define ACTION_DEFINITION(ActionSpec) \
43 | typedef typename ActionSpec::_action_goal_type ActionGoal; \
44 | typedef typename ActionGoal::_goal_type Goal; \
45 | typedef typename ActionSpec::_action_result_type ActionResult; \
46 | typedef typename ActionResult::_result_type Result; \
47 | typedef typename ActionSpec::_action_feedback_type ActionFeedback; \
48 | typedef typename ActionFeedback::_feedback_type Feedback; \
49 | \
50 | typedef boost::shared_ptr ActionGoalConstPtr; \
51 | typedef boost::shared_ptr ActionGoalPtr; \
52 | typedef boost::shared_ptr GoalConstPtr; \
53 | typedef boost::shared_ptr GoalPtr; \
54 | \
55 | typedef boost::shared_ptr ActionResultConstPtr; \
56 | typedef boost::shared_ptr ActionResultPtr; \
57 | typedef boost::shared_ptr ResultConstPtr; \
58 | typedef boost::shared_ptr ResultPtr; \
59 | \
60 | typedef boost::shared_ptr ActionFeedbackConstPtr; \
61 | typedef boost::shared_ptr ActionFeedbackPtr; \
62 | typedef boost::shared_ptr FeedbackConstPtr; \
63 | typedef boost::shared_ptr FeedbackPtr;
64 | } // namespace actionlib
65 | #endif // ACTIONLIB__ACTION_DEFINITION_H_
66 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/service_server_imp.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2009, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_
38 | #define ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_
39 |
40 | #include
41 |
42 | namespace actionlib
43 | {
44 |
45 | template
46 | ServiceServer advertiseService(ros::NodeHandle n, std::string name,
47 | boost::function service_cb)
49 | {
50 | boost::shared_ptr server_ptr(new ServiceServerImpT(n, name,
51 | service_cb));
52 | return ServiceServer(server_ptr);
53 | }
54 |
55 | template
56 | ServiceServerImpT::ServiceServerImpT(ros::NodeHandle n, std::string name,
57 | boost::function service_cb)
58 | : service_cb_(service_cb)
59 | {
60 | as_ = boost::shared_ptr >(new ActionServer(n, name,
61 | boost::bind(&ServiceServerImpT::goalCB, this, boost::placeholders::_1), false));
62 | as_->start();
63 | }
64 |
65 | template
66 | void ServiceServerImpT::goalCB(GoalHandle goal)
67 | {
68 | goal.setAccepted("This goal has been accepted by the service server");
69 |
70 | // we need to pass the result into the users callback
71 | Result r;
72 | if (service_cb_(*(goal.getGoal()), r)) {
73 | goal.setSucceeded(r, "The service server successfully processed the request");
74 | } else {
75 | goal.setAborted(r, "The service server failed to process the request");
76 | }
77 | }
78 |
79 | } // namespace actionlib
80 | #endif // ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_
81 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/server/service_server.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | *
3 | * Software License Agreement (BSD License)
4 | *
5 | * Copyright (c) 2009, Willow Garage, Inc.
6 | * All rights reserved.
7 | *
8 | * Redistribution and use in source and binary forms, with or without
9 | * modification, are permitted provided that the following conditions
10 | * are met:
11 | *
12 | * * Redistributions of source code must retain the above copyright
13 | * notice, this list of conditions and the following disclaimer.
14 | * * Redistributions in binary form must reproduce the above
15 | * copyright notice, this list of conditions and the following
16 | * disclaimer in the documentation and/or other materials provided
17 | * with the distribution.
18 | * * Neither the name of Willow Garage, Inc. nor the names of its
19 | * contributors may be used to endorse or promote products derived
20 | * from this software without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | * POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | * Author: Eitan Marder-Eppstein
36 | *********************************************************************/
37 | #ifndef ACTIONLIB__SERVER__SERVICE_SERVER_H_
38 | #define ACTIONLIB__SERVER__SERVICE_SERVER_H_
39 |
40 | #include
41 | #include
42 |
43 | #include
44 |
45 | namespace actionlib
46 | {
47 |
48 | class ServiceServerImp
49 | {
50 | public:
51 | ServiceServerImp() {}
52 | virtual ~ServiceServerImp() {}
53 | };
54 |
55 | class ServiceServer
56 | {
57 | public:
58 | ServiceServer(boost::shared_ptr server)
59 | : server_(server) {}
60 |
61 | private:
62 | boost::shared_ptr server_;
63 | };
64 |
65 | template
66 | ServiceServer advertiseService(ros::NodeHandle n, std::string name,
67 | boost::function service_cb);
69 |
70 | template
71 | class ServiceServerImpT : public ServiceServerImp
72 | {
73 | public:
74 | // generates typedefs that we'll use to make our lives easier
75 | ACTION_DEFINITION(ActionSpec)
76 |
77 | typedef typename ActionServer::GoalHandle GoalHandle;
78 |
79 | ServiceServerImpT(ros::NodeHandle n, std::string name,
80 | boost::function service_cb);
81 | void goalCB(GoalHandle g);
82 |
83 | private:
84 | boost::shared_ptr > as_;
85 | boost::function service_cb_;
86 | };
87 |
88 | } // namespace actionlib
89 |
90 | // include the implementation
91 | #include
92 | #endif // ACTIONLIB__SERVER__SERVICE_SERVER_H_
93 |
--------------------------------------------------------------------------------
/actionlib/test/ref_simple_server.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | # Copyright (c) 2009, Willow Garage, Inc.
3 | # All rights reserved.
4 | #
5 | # Redistribution and use in source and binary forms, with or without
6 | # modification, are permitted provided that the following conditions are met:
7 | #
8 | # * Redistributions of source code must retain the above copyright
9 | # notice, this list of conditions and the following disclaimer.
10 | # * Redistributions in binary form must reproduce the above copyright
11 | # notice, this list of conditions and the following disclaimer in the
12 | # documentation and/or other materials provided with the distribution.
13 | # * Neither the name of the Willow Garage, Inc. nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 | # Author: Alexander Sorokin.
30 | # Based on code from ref_server.cpp by Vijay Pradeep
31 | PKG = 'actionlib'
32 | import rospy
33 |
34 | from actionlib.simple_action_server import SimpleActionServer
35 | from actionlib.msg import TestAction, TestFeedback
36 |
37 |
38 | class RefSimpleServer (SimpleActionServer):
39 |
40 | def __init__(self, name):
41 | action_spec = TestAction
42 | SimpleActionServer.__init__(
43 | self, name, action_spec, self.goal_callback, False)
44 | self.start()
45 | rospy.loginfo("Creating SimpleActionServer [%s]\n", name)
46 |
47 | def goal_callback(self, goal):
48 | rospy.loginfo("Got goal %d", int(goal.goal))
49 | if goal.goal == 1:
50 | self.set_succeeded(None, "The ref server has succeeded")
51 | elif goal.goal == 2:
52 | self.set_aborted(None, "The ref server has aborted")
53 | elif goal.goal == 3:
54 | self.set_aborted(None, "The simple action server can't reject goals")
55 | elif goal.goal == 4:
56 | self.set_aborted(None, "Simple server can't save goals")
57 | elif goal.goal == 5:
58 | self.set_aborted(None, "Simple server can't save goals")
59 | elif goal.goal == 6:
60 | self.set_aborted(None, "Simple server can't save goals")
61 | elif goal.goal == 7:
62 | self.set_aborted(None, "Simple server can't save goals")
63 | elif goal.goal == 8:
64 | self.set_aborted(None, "Simple server can't save goals")
65 | elif goal.goal == 9:
66 | rospy.sleep(1)
67 | rospy.loginfo("Sending feedback")
68 | self.publish_feedback(TestFeedback(9)) # by the goal ID
69 | rospy.sleep(1)
70 | self.set_succeeded(None, "The ref server has succeeded")
71 | else:
72 | pass
73 |
74 |
75 | if __name__ == "__main__":
76 | rospy.init_node("ref_simple_server")
77 | ref_server = RefSimpleServer("reference_simple_action")
78 |
79 | rospy.spin()
80 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/client/simple_goal_state.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #ifndef ACTIONLIB__CLIENT__SIMPLE_GOAL_STATE_H_
36 | #define ACTIONLIB__CLIENT__SIMPLE_GOAL_STATE_H_
37 |
38 | #include
39 | #include "ros/console.h"
40 |
41 | namespace actionlib
42 | {
43 |
44 | /**
45 | * \brief Thin wrapper around an enum in order providing a simplified version of the
46 | * communication state, but with less states than CommState
47 | **/
48 | class SimpleGoalState
49 | {
50 | public:
51 | //! \brief Defines the various states the SimpleGoalState can be in
52 | enum StateEnum
53 | {
54 | PENDING,
55 | ACTIVE,
56 | DONE
57 | };
58 |
59 | SimpleGoalState(const StateEnum & state)
60 | : state_(state) {}
61 |
62 | inline bool operator==(const SimpleGoalState & rhs) const
63 | {
64 | return state_ == rhs.state_;
65 | }
66 |
67 | inline bool operator==(const SimpleGoalState::StateEnum & rhs) const
68 | {
69 | return state_ == rhs;
70 | }
71 |
72 | inline bool operator!=(const SimpleGoalState::StateEnum & rhs) const
73 | {
74 | return !(*this == rhs);
75 | }
76 |
77 | inline bool operator!=(const SimpleGoalState & rhs) const
78 | {
79 | return !(*this == rhs);
80 | }
81 |
82 | std::string toString() const
83 | {
84 | switch (state_) {
85 | case PENDING:
86 | return "PENDING";
87 | case ACTIVE:
88 | return "ACTIVE";
89 | case DONE:
90 | return "DONE";
91 | default:
92 | ROS_ERROR_NAMED("actionlib", "BUG: Unhandled SimpleGoalState: %u", state_);
93 | break;
94 | }
95 | return "BUG-UNKNOWN";
96 | }
97 |
98 | StateEnum state_;
99 |
100 | private:
101 | SimpleGoalState();
102 | };
103 |
104 | } // namespace actionlib
105 |
106 | #endif // ACTIONLIB__CLIENT__SIMPLE_GOAL_STATE_H_
107 |
--------------------------------------------------------------------------------
/actionlib/include/actionlib/client/connection_monitor.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2008, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #ifndef ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
36 | #define ACTIONLIB__CLIENT__CONNECTION_MONITOR_H_
37 |
38 | #include
39 | #include
40 |
41 | #include
42 |
43 | #include
44 | #include
45 |
46 | #include
47 | #include
48 | #include