Skip to content

Commit

Permalink
Merge pull request #7 from chargerKong/dashing-to-upstream
Browse files Browse the repository at this point in the history
Port tianracer_bringup to ROS2
  • Loading branch information
tianb03 authored Nov 11, 2021
2 parents a33450b + 9cb9dc7 commit 8aec398
Show file tree
Hide file tree
Showing 9 changed files with 196 additions and 293 deletions.
208 changes: 16 additions & 192 deletions tianracer_bringup/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,207 +1,31 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(tianracer_bringup)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs
# )

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES tianracer_bringup
# CATKIN_DEPENDS roscpp rospy std_msgs
# DEPENDS system_lib
)
## Find dependencies
find_package(ament_cmake REQUIRED)

string(ASCII 27 Esc)
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/99.my_tianracer.sh.em")
catkin_add_env_hooks(99.my_tianracer SHELLS sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks)
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/99.my_tianracer.sh.in")
ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/99.my_tianracer.sh.in")
message("--${Esc}[1;34m *** Add Customized Tianbot Environment Variables *** ${Esc}[0m")
else()
catkin_add_env_hooks(99.default_tianracer SHELLS sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks)
ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/99.default_tianracer.sh.in")
message("--${Esc}[1;33m *** Attention! Using default Tianbot Environment Variables *** ${Esc}[0m")
endif()
###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
install(DIRECTORY launch param
DESTINATION share/${PROJECT_NAME}
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/tianracer_bringup.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/tianracer_bringup_node.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_racecar_bringup.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
ament_package()
30 changes: 0 additions & 30 deletions tianracer_bringup/env-hooks/99.default_tianracer.sh.em

This file was deleted.

13 changes: 13 additions & 0 deletions tianracer_bringup/env-hooks/99.default_tianracer.sh.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# generated from ros_environment/env-hooks/1.ros_version.sh.in

export TIANRACER_BASE=compact # compact, standard, fullsize, customized.
export TIANRACER_BASE_PORT=/dev/tianbot_racecar # /dev/ttyUSB1
export TIANRACER_STEERING_DIRECTION=normal # compact, standard, fullsize, customized.
export TIANRACER_THROTTLE_DIRECTION=normal # compact, standard, fullsize, customized.
export TIANRACER_BRIDGE=disabled # enabled,disabled
export TIANRACER_RGBD_CAMERA=none # realsense_d415, realsense_d435, astra, astra_pro, xtion, none
export TIANRACER_VIDEO_DEVICE=none # /dev/video0 for most of the usb_cams.If you want init usb_cam in jet_cam, this should be set to none.
export TIANRACER_LIDAR=rplidar_a1 # rplidar, velodyne_vlp16, osight, rslidar, hokuyo, sick, etc..
export TIANRACER_LIDAR_MODEL=a1 # a1, a2, a3, iexxx, vlp16, etc...
export TIANRACER_LIDAR_PORT=/dev/tianbot_rplidar # /dev/ttyUSB0
export TIANRACER_GPS=none # none, nmea0183
6 changes: 3 additions & 3 deletions tianracer_bringup/install/_bin_/tianracer_bringup.sh
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@

#IP=$(ip addr show eth0 | grep -w inet | awk '{print $2}' | awk -F / '{print $1}')

source /home/tianbot/tianbot_ws/devel/setup.bash
source /home/tianbot/tianbot_ws/install/local_setup.bash

export ROS_MASTER_URI=http://localhost:11311
# export ROS_MASTER_URI=http://localhost:11311

#export ROS_IP=${IP}

roslaunch tianracer_bringup tianracer_bringup.launch
ros2 launch tianracer_bringup tianracer_bringup.launch.py
84 changes: 84 additions & 0 deletions tianracer_bringup/launch/includes/lidar/rplidar.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
#!/usr/bin/env python3

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch.actions import OpaqueFunction

def launch_setup(context, *args, **kwargs):
serial_port = LaunchConfiguration('serial_port', default=\
os.environ.get("TIANRACER_LIDAR_PORT", "/dev/ttyUSB0"))
# serial_baudrate = LaunchConfiguration('serial_baudrate', default='115200') #for A1/A2 is 115200
frame_id = LaunchConfiguration('frame_id', default='laser')
inverted = LaunchConfiguration('inverted', default='false')
angle_compensate = LaunchConfiguration('angle_compensate', default='true')
model_env = LaunchConfiguration('model', default=\
os.environ.get("TIANRACER_LIDAR_MODEL", "a1")).perform(context) # for compatibility
serial_baudrate = 256000 if "a3" in model_env else 115200
scan_mode = "Sensitivity" if "a3" in model_env else "Boost"

return LaunchDescription([

DeclareLaunchArgument(
'serial_port',
default_value=serial_port,
description='Specifying usb port to connected lidar'),

DeclareLaunchArgument(
'frame_id',
default_value=frame_id,
description='Specifying frame_id of lidar'),

DeclareLaunchArgument(
'model',
default_value=model_env,
description='Specifying model of lidar'),

DeclareLaunchArgument(
'inverted',
default_value=inverted,
description='Specifying whether or not to invert scan data'),

DeclareLaunchArgument(
'angle_compensate',
default_value=angle_compensate,
description='Specifying whether or not to enable angle_compensate of scan data'),


Node(
package='rplidar_ros2',
node_executable='rplidar_scan_publisher',
name='rplidar_scan_publisher',
parameters=[{'serial_port': serial_port,
'serial_baudrate': serial_baudrate,
'frame_id': frame_id,
'inverted': inverted,
'angle_compensate': angle_compensate,
'scan_mode': scan_mode}],
output='screen',
remappings = [('scan', 'scan_raw')]),

Node(
package="laser_filters",
node_executable="scan_to_scan_filter_chain",
name="scan_to_scan_filter_chain",
parameters=[
os.path.join(
get_package_share_directory("tianracer_bringup"),
"param", "tianbot_laser_config.yaml"
)
],
remappings=[('scan', 'scan_raw'),
('scan_filtered', 'scan'),]
)
])

def generate_launch_description():
return LaunchDescription([
OpaqueFunction(function=launch_setup),
])

29 changes: 29 additions & 0 deletions tianracer_bringup/launch/lidar.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#!/usr/bin/env python3

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource


def generate_launch_description():
lidar = os.environ.get("TIANRACER_LIDAR", "rplidar_a1")
model = os.environ.get("TIANRACER_LIDAR_MODEL", "a1")
ld = LaunchDescription()
if "rplidar" in lidar:
ld.add_action(IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(
get_package_share_directory("tianracer_bringup"),
'launch','includes','lidar', 'rplidar.launch.py')),
launch_arguments={'model': model}.items(),
))
## TODO
# if “osight” in lidar
# if “velodyne” in lidar
# if “rslidar” in lidar



return ld
Loading

0 comments on commit 8aec398

Please sign in to comment.