Skip to content

Commit d2ee107

Browse files
authored
Port over Wiimote to ROS2 Foxy (#175)
* Port over Wiimote to ROS2 Foxy * update PR based on feedbacks
1 parent e8e7f9c commit d2ee107

37 files changed

+2519
-4599
lines changed

wiimote/AMENT_IGNORE

Whitespace-only changes.

wiimote/CMakeLists.txt

Lines changed: 86 additions & 79 deletions
Original file line numberDiff line numberDiff line change
@@ -1,94 +1,101 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(wiimote)
33

4-
set(CMAKE_CXX_STANDARD 11)
5-
set(CMAKE_CXX_STANDARD_REQUIRED ON)
6-
7-
# Save the command line compile commands in the build output
8-
set(CMAKE_EXPORT_COMPILE_COMMANDS 1)
9-
# View the makefile commands during build
10-
#set(CMAKE_VERBOSE_MAKEFILE on)
11-
12-
# Set compile flags
13-
set(CMAKE_CXX_FLAGS "-fPIE -fPIC -O2 -D_FORTIFY_SOURCE=2 -fstack-protector -Wformat -Wformat-security -Wall ${CMAKE_CXX_FLAGS}")
14-
# Flags executables
15-
set(CMAKE_EXE_LINKER_FLAGS "-pie -z noexecstack -z relro -z now")
16-
# Flags shared libraries
17-
set(CMAKE_SHARED_LINKER_FLAGS "-z noexecstack -z relro -z now ${CMAKE_SHARED_LINKER_FLAGS}")
18-
19-
# Load catkin and all dependencies required for this package
20-
set(CATKIN_DEPS geometry_msgs sensor_msgs std_msgs std_srvs rospy roscpp roslib genmsg roslint)
21-
find_package(catkin REQUIRED ${CATKIN_DEPS})
22-
23-
catkin_python_setup()
24-
25-
# generate the messages
26-
add_message_files(
27-
DIRECTORY msg
28-
FILES
29-
IrSourceInfo.msg
30-
State.msg
31-
TimedSwitch.msg
32-
)
4+
# Default to C99
5+
if(NOT CMAKE_C_STANDARD)
6+
set(CMAKE_C_STANDARD 99)
7+
endif()
8+
9+
# Default to C++14
10+
if(NOT CMAKE_CXX_STANDARD)
11+
set(CMAKE_CXX_STANDARD 14)
12+
endif()
13+
14+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
15+
add_compile_options(-Wall -Wextra -Wpedantic)
16+
endif()
17+
18+
find_library(BLUETOOTH_LIB bluetooth)
19+
if(BLUETOOTH_LIB)
20+
message(STATUS "Found bluetooth library.")
21+
else()
22+
message(FATAL_ERROR "bluetooth library not found.")
23+
endif()
24+
25+
find_library(CWIID_LIB cwiid)
26+
if(CWIID_LIB)
27+
message(STATUS "Found cwiid library.")
28+
else()
29+
message(FATAL_ERROR "cwiid library not found.")
30+
endif()
3331

34-
generate_messages(DEPENDENCIES geometry_msgs std_msgs sensor_msgs)
35-
36-
# ROS Lint the code
37-
roslint_cpp()
38-
roslint_python()
39-
40-
###################################
41-
## catkin specific configuration ##
42-
###################################
43-
## The catkin_package macro generates cmake config files for your package
44-
## Declare things to be passed to dependent projects
45-
## INCLUDE_DIRS: uncomment this if you package contains header files
46-
## LIBRARIES: libraries you create in this project that dependent projects also need
47-
## CATKIN_DEPENDS: catkin_packages dependent projects also need
48-
## DEPENDS: system dependencies of this project that dependent projects also need
49-
catkin_package(
50-
INCLUDE_DIRS include
51-
CATKIN_DEPENDS
52-
geometry_msgs
53-
sensor_msgs
54-
std_msgs
55-
std_srvs
32+
33+
find_package(ament_cmake REQUIRED)
34+
find_package(ament_cmake_auto REQUIRED)
35+
36+
ament_auto_find_build_dependencies(
37+
REQUIRED
38+
rclcpp
39+
rclcpp_components
40+
rclcpp_lifecycle
41+
sensor_msgs
42+
std_srvs
43+
wiimote_msgs
5644
)
5745

58-
## Specify additional locations of header files
59-
include_directories(
60-
include
61-
${catkin_INCLUDE_DIRS}
46+
## C++ Wiimote Lib
47+
set(wiimote_lib_HEADERS
48+
include/wiimote/wiimote_controller.hpp
49+
include/wiimote/stat_vector_3d.hpp)
50+
51+
set(wiimote_lib_SOURCES
52+
src/wiimote_controller.cpp
53+
src/stat_vector_3d.cpp)
54+
55+
ament_auto_add_library(wiimote_lib SHARED ${wiimote_lib_HEADERS} ${wiimote_lib_SOURCES})
56+
target_link_libraries(wiimote_lib bluetooth cwiid)
57+
58+
rclcpp_components_register_node(
59+
wiimote_lib
60+
PLUGIN "WiimoteNode"
61+
EXECUTABLE wiimote_node
6262
)
63+
## End C++ Wiimote Lib
6364

64-
## C++ Wiimote Node: Declare cpp executables
65-
add_executable(wiimote_node src/wiimote_controller.cpp src/stat_vector_3d.cpp)
66-
target_link_libraries(wiimote_node ${catkin_LIBRARIES} bluetooth cwiid)
67-
add_dependencies(wiimote_node wiimote_generate_messages_cpp)
68-
## End of C++ Wiimote Node
65+
# C++ Teleop for Wiimote Node: Declare cpp executables
66+
set(teleop_wiimote_HEADERS include/wiimote/teleop_wiimote.hpp)
67+
set(teleop_wiimote_SOURCES src/teleop_wiimote.cpp)
68+
ament_auto_add_library(teleop_wiimote SHARED ${teleop_wiimote_HEADERS} ${teleop_wiimote_SOURCES})
6969

70-
## C++ Teleop for Wiimote Node: Declare cpp executables
71-
add_executable(teleop_wiimote src/teleop_wiimote.cpp)
72-
target_link_libraries(teleop_wiimote ${catkin_LIBRARIES})
73-
add_dependencies(teleop_wiimote wiimote_generate_messages_cpp)
74-
## End C++ Teleop for Wiimote Node
70+
rclcpp_components_register_node(
71+
teleop_wiimote
72+
PLUGIN "TeleopWiimote"
73+
EXECUTABLE teleop_wiimote_node
74+
)
75+
# End C++ Teleop for Wiimote Node
7576

76-
if(CATKIN_ENABLE_TESTING)
77-
roslint_add_test()
77+
if(BUILD_TESTING)
78+
find_package(ament_lint_auto REQUIRED)
79+
ament_lint_auto_find_test_dependencies()
7880
endif()
7981

80-
# Install launch files
81-
install(DIRECTORY launch/
82-
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
83-
)
82+
# Install lib
83+
install(TARGETS wiimote_lib teleop_wiimote
84+
ARCHIVE DESTINATION lib
85+
LIBRARY DESTINATION lib
86+
RUNTIME DESTINATION bin)
87+
install(DIRECTORY include/ DESTINATION include)
88+
89+
# Install launch and config files
90+
install(DIRECTORY launch config
91+
DESTINATION share/${PROJECT_NAME})
8492

85-
# Install targets
86-
install(PROGRAMS nodes/feedbackTester.py nodes/wiimote_node.py
87-
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
88-
)
89-
## Mark executables and/or libraries for installation
93+
# Install Executables
9094
install(TARGETS wiimote_node
91-
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
92-
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
93-
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
95+
DESTINATION lib/${PROJECT_NAME})
96+
97+
install(PROGRAMS nodes/feedback_tester.py
98+
DESTINATION lib/${PROJECT_NAME}
9499
)
100+
101+
ament_package()
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
/**:
2+
ros__parameters:
3+
linear:
4+
x:
5+
max_velocity: 0.65024
6+
min_velocity: -0.65024
7+
throttle_percent: 0.75
8+
angular:
9+
z:
10+
max_velocity: 3.14159265358979323846
11+
min_velocity: -3.14159265358979323846
12+
throttle_percent: 0.75

wiimote/config/wiimote_params.yaml

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,9 @@
1+
/**:
2+
ros__parameters:
3+
bluetooth_addr: "00:00:00:00:00:00"
4+
pair_timeout: -1
5+
check_connection_interval: 1.0
6+
publish_interval: .2
7+
require_nunchuk: true
8+
require_classic: false
9+
require_motionplus: false

wiimote/include/wiimote/stat_vector_3d.h renamed to wiimote/include/wiimote/stat_vector_3d.hpp

Lines changed: 18 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,20 @@
1+
// Copyright 2020 Intel Corporation
2+
// This program is free software: you can redistribute it and/or modify
3+
// it under the terms of the GNU General Public License as published by
4+
// the Free Software Foundation, either version 3 of the License, or
5+
// (at your option) any later version.
6+
//
7+
// This program is distributed in the hope that it will be useful,
8+
// but WITHOUT ANY WARRANTY; without even the implied warranty of
9+
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10+
// GNU General Public License for more details.
11+
//
12+
// You should have received a copy of the GNU General Public License
13+
// along with this program. If not, see <https://www.gnu.org/licenses/>.
14+
115
/*
216
* Three dimensional statistic vector for use with the
317
* for ROS Node which interfaces with a wiimote control unit.
4-
* Copyright (c) 2016, Intel Corporation.
5-
*
6-
* This program is free software; you can redistribute it and/or modify it
7-
* under the terms and conditions of the GNU General Public License,
8-
* version 2, as published by the Free Software Foundation.
9-
*
10-
* This program is distributed in the hope it will be useful, but WITHOUT
11-
* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
12-
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13-
* more details.
1418
*/
1519

1620
/*
@@ -22,13 +26,11 @@
2226
*/
2327

2428
#pragma once
25-
#ifndef WIIMOTE_STAT_VECTOR_3D_H
26-
#define WIIMOTE_STAT_VECTOR_3D_H
29+
#ifndef WIIMOTE__STAT_VECTOR_3D_HPP_
30+
#define WIIMOTE__STAT_VECTOR_3D_HPP_
31+
2732

2833
#include <vector>
29-
#include <numeric>
30-
#include <algorithm>
31-
#include <math.h>
3234

3335
// The vector of 3 values collected to generate:
3436
// mean, standard deviation, and variance.
@@ -60,4 +62,4 @@ class StatVector3d
6062
std::vector<int> z_;
6163
};
6264

63-
#endif // WIIMOTE_STAT_VECTOR_3D_H
65+
#endif // WIIMOTE__STAT_VECTOR_3D_HPP_

wiimote/include/wiimote/teleop_wiimote.h

Lines changed: 0 additions & 70 deletions
This file was deleted.

0 commit comments

Comments
 (0)