Skip to content

Commit 0bff20a

Browse files
Schnilzclalancette
andauthored
spacenav node changed for ros2 (#194)
* spacenav node changed for ros2 Co-authored-by: Chris Lalancette <[email protected]>
1 parent b8d4c13 commit 0bff20a

18 files changed

+668
-395
lines changed

spacenav_node/CHANGELOG.rst renamed to spacenav/CHANGELOG.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
1-
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2-
Changelog for package spacenav_node
3-
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package spacenav
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

55
1.13.0 (2019-06-24)
66
-------------------

spacenav/CMakeLists.txt

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(spacenav)
3+
4+
# Default to C++14
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 14)
7+
endif()
8+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
9+
add_compile_options(-Wall -Wextra -Wpedantic)
10+
endif()
11+
12+
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
13+
14+
find_package(ament_cmake REQUIRED)
15+
find_package(geometry_msgs REQUIRED)
16+
find_package(rclcpp REQUIRED)
17+
find_package(rclcpp_components REQUIRED)
18+
find_package(sensor_msgs REQUIRED)
19+
find_package(SPNAV REQUIRED)
20+
21+
include_directories(include)
22+
add_library(spacenav
23+
SHARED
24+
src/spacenav.cpp)
25+
target_include_directories(spacenav
26+
PUBLIC
27+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
28+
$<INSTALL_INTERFACE:include>)
29+
ament_target_dependencies(spacenav
30+
"geometry_msgs"
31+
"rclcpp"
32+
"sensor_msgs")
33+
34+
target_link_libraries(spacenav spnav)
35+
36+
# Install targets
37+
install(TARGETS spacenav
38+
ARCHIVE DESTINATION lib/${PROJECT_NAME}
39+
LIBRARY DESTINATION lib/${PROJECT_NAME}
40+
RUNTIME DESTINATION lib/${PROJECT_NAME}
41+
)
42+
43+
install(DIRECTORY
44+
launch
45+
DESTINATION share/${PROJECT_NAME}/
46+
)
47+
48+
rclcpp_components_register_node(spacenav
49+
PLUGIN "spacenav::Spacenav"
50+
EXECUTABLE spacenav_node)
51+
52+
if(BUILD_TESTING)
53+
find_package(ament_lint_auto REQUIRED)
54+
set(ament_cmake_copyright_FOUND TRUE)
55+
ament_lint_auto_find_test_dependencies()
56+
endif()
57+
58+
59+
ament_package()

spacenav_node/LICENSE renamed to spacenav/LICENSE

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
BSD 3-Clause License
22

33
Copyright (c) 2008, Willow Garage, Inc.
4+
Copyright (c) 2020, Nils Schulte
45
All rights reserved.
56

67
Redistribution and use in source and binary forms, with or without

spacenav/README.md

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
# Spacenav Node #
2+
##### Published topics #####
3+
* `spacenav/offset` (geometry_msgs/msg/Vector3)
4+
5+
Publishes the linear component of the joystick's position. Approximately normalized to a range of -1 to 1.
6+
* `spacenav/rot_offset`(geometry_msgs/msg/Vector3)
7+
8+
Publishes the angular component of the joystick's position. Approximately normalized to a range of -1 to 1.
9+
* `spacenav/twist` (geometry_msgs/msg/Twist)
10+
11+
Combines offset and rot_offset into a single message.
12+
* `spacenav/joy` (sensor_msgs/msg/Joy)
13+
14+
Outputs the spacenav's six degrees of freedom and its buttons as a joystick message.
15+
16+
##### Parameters #####
17+
sets values to zero when the spacenav is not moving
18+
* `zero_when_static` (boolean, default: true)
19+
* `static_count_threshold` (int, default: 30)
20+
21+
The number of polls needed to be done before the device is considered "static"
22+
* `static_trans_deadband` (float, default: 0.1)
23+
24+
sets the translational deadband
25+
* `static_rot_deadband` (float, default: 0.1)
26+
27+
sets the rotational deadband
28+
* `linear_scale/x` (float, default: 1)
29+
* `linear_scale/y` (float, default: 1)
30+
* `linear_scale/z` (float, default: 1)
31+
32+
sets the scale of the linear output
33+
* `angular_scale/x` (float, default: 1)
34+
* `angular_scale/y` (float, default: 1)
35+
* `angular_scale/z` (float, default: 1)
36+
sets the scale of the angular output
37+
38+
## Running the spacenav node ##
39+
40+
Running the node is straightforward
41+
```
42+
$ ros2 run spacenav spacenav
43+
```
44+
The node is now publishing to the topics listed above.

spacenav/cmake/FindSPNAV.cmake

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
# Find the spnav library and header.
2+
#
3+
# Sets the usual variables expected for find_package scripts:
4+
#
5+
# spnav_INCLUDE_DIR - header location
6+
# spnav_LIBRARIES - library to link against
7+
# spnav_FOUND - true if pugixml was found.
8+
9+
if(UNIX)
10+
11+
find_path(spnav_INCLUDE_DIR spnav.h)
12+
13+
find_library(spnav_LIBRARY
14+
NAMES
15+
spnav libspnav
16+
)
17+
18+
# Support the REQUIRED and QUIET arguments, and set spnav_FOUND if found.
19+
include(FindPackageHandleStandardArgs)
20+
find_package_handle_standard_args(SPNAV DEFAULT_MSG
21+
spnav_LIBRARY
22+
spnav_INCLUDE_DIR)
23+
24+
if(spnav_FOUND)
25+
set(spnav_LIBRARIES ${spnav_LIBRARY})
26+
endif()
27+
28+
mark_as_advanced(
29+
spnav_LIBRARY
30+
spnav_INCLUDE_DIR)
31+
32+
endif()
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
/*
2+
* Copyright (c) 2008, 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+
30+
#ifndef SPACENAV__SPACENAV_HPP_
31+
#define SPACENAV__SPACENAV_HPP_
32+
33+
#include <rclcpp/rclcpp.hpp>
34+
35+
#include <geometry_msgs/msg/twist.hpp>
36+
#include <geometry_msgs/msg/vector3.hpp>
37+
#include <sensor_msgs/msg/joy.hpp>
38+
39+
#include "spnav.h" // NOLINT
40+
41+
namespace spacenav
42+
{
43+
44+
class Spacenav final : public rclcpp::Node
45+
{
46+
public:
47+
explicit Spacenav(const rclcpp::NodeOptions & options);
48+
49+
~Spacenav();
50+
51+
private:
52+
void poll_spacenav();
53+
54+
OnSetParametersCallbackHandle::SharedPtr callback_handler;
55+
56+
rclcpp::TimerBase::SharedPtr timer_;
57+
58+
rclcpp::Publisher<geometry_msgs::msg::Vector3>::SharedPtr publisher_offset;
59+
60+
rclcpp::Publisher<geometry_msgs::msg::Vector3>::SharedPtr publisher_rot_offset;
61+
62+
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_twist;
63+
64+
rclcpp::Publisher<sensor_msgs::msg::Joy>::SharedPtr publisher_joy;
65+
66+
bool spacenav_is_open = false;
67+
68+
double full_scale;
69+
double linear_scale[3];
70+
double angular_scale[3];
71+
72+
int static_count_threshold;
73+
bool zero_when_static;
74+
double static_trans_deadband;
75+
double static_rot_deadband;
76+
77+
spnav_event sev;
78+
bool joy_stale = false;
79+
int no_motion_count = 0;
80+
bool motion_stale = false;
81+
double normed_vx = 0;
82+
double normed_vy = 0;
83+
double normed_vz = 0;
84+
double normed_wx = 0;
85+
double normed_wy = 0;
86+
double normed_wz = 0;
87+
};
88+
89+
} // namespace spacenav
90+
91+
#endif // SPACENAV__SPACENAV_HPP_

spacenav/launch/classic-launch.py

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
# Copyright (c) 2008, 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 launch import LaunchDescription
29+
from launch_ros.actions import Node
30+
31+
32+
def generate_launch_description():
33+
return LaunchDescription([
34+
Node(package='spacenav', executable='spacenav',
35+
name='spacenav', namespace='', output='screen',
36+
parameters=[{'zero_when_static': True,
37+
'static_count_threshold': 30}]),
38+
])
Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
# Copyright (c) 2008, 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 launch import LaunchDescription
29+
from launch_ros.actions import Node
30+
31+
32+
def generate_launch_description():
33+
return LaunchDescription([
34+
Node(package='spacenav', executable='spacenav',
35+
name='spacenav', namespace='', output='screen',
36+
parameters=[{'zero_when_static': False,
37+
'static_trans_deadband': 0.0,
38+
'static_rot_deadband': 0.0}]),
39+
])
Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
# Copyright (c) 2008, 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 launch import LaunchDescription
29+
from launch_ros.actions import Node
30+
31+
32+
def generate_launch_description():
33+
return LaunchDescription([
34+
Node(package='spacenav', executable='spacenav',
35+
name='spacenav', namespace='', output='screen',
36+
parameters=[{'zero_when_static': False,
37+
'static_count_threshold': 30,
38+
'static_trans_deadband': 40.0,
39+
'static_rot_deadband': 40.0}]),
40+
])

0 commit comments

Comments
 (0)