Skip to content

Commit

Permalink
Merge pull request #4 from chargerKong/dashing-to-upstream
Browse files Browse the repository at this point in the history
Port tianracer_core to ROS2
  • Loading branch information
tianb03 authored Nov 6, 2021
2 parents 8cc6dfb + 1f31ea3 commit 6815d03
Show file tree
Hide file tree
Showing 17 changed files with 537 additions and 499 deletions.
251 changes: 54 additions & 197 deletions tianracer_core/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,212 +1,69 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(tianracer_core)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()

## 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
geometry_msgs
nav_msgs
roscpp
rospy
std_msgs
tf
sensor_msgs
ackermann_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 ##
################################################
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

## 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
# geometry_msgs# nav_msgs# 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

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )

###################################
## 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 tianboard
# CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs
# DEPENDS system_lib
)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
include/tianboard
${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/tianboard.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/tianboard.cpp src/serial.cpp src/main.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}
pthread
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(ackermann_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)

set(dependencies
geometry_msgs
rclcpp
std_msgs
ackermann_msgs
tf2_ros
nav_msgs
tf2_geometry_msgs
sensor_msgs
)

#############
## 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
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
add_executable(${PROJECT_NAME}_node src/main.cpp src/tianboard.cpp src/serial.cpp)
target_link_libraries(${PROJECT_NAME}_node pthread)

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
ament_target_dependencies(${PROJECT_NAME}_node ${dependencies})

## 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 ##
#############
install(TARGETS
${PROJECT_NAME}_node
DESTINATION lib/${PROJECT_NAME}
)

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_tianboard.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
install(DIRECTORY include launch param
DESTINATION share/${PROJECT_NAME}
)

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
45 changes: 0 additions & 45 deletions tianracer_core/include/tianboard/tianboard.h

This file was deleted.

46 changes: 46 additions & 0 deletions tianracer_core/include/tianboard/tianboard.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
#ifndef __TIANBOARD_H__
#define __TIANBOARD_H__

#include <rclcpp/rclcpp.hpp>
#include "serial.h"
#include <geometry_msgs/msg/twist.hpp>
#include "geometry_msgs/msg/pose2_d.hpp"
#include <geometry_msgs/msg/transform_stamped.hpp>
#include "boost/bind.hpp"
#include "boost/function.hpp"

#include <nav_msgs/msg/odometry.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include "sensor_msgs/msg/imu.hpp"
#include <ackermann_msgs/msg/ackermann_drive.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#define DEFAULT_SERIAL_DEVICE "/dev/ttyUSB1"

class Tianboard: public rclcpp::Node {
public:
Tianboard();
~Tianboard(){};
private:
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_pub_;
rclcpp::Publisher<geometry_msgs::msg::Pose2D>::SharedPtr uwb_pub_;
rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr imu_pub_;
rclcpp::Subscription<ackermann_msgs::msg::AckermannDrive>::SharedPtr ackermann_sub_;
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
rclcpp::TimerBase::SharedPtr heart_timer_;
rclcpp::TimerBase::SharedPtr communication_timer_;
Serial serial_;
void ackermannCallback(const ackermann_msgs::msg::AckermannDrive::SharedPtr msg);
void serialDataProc(uint8_t *data, unsigned int data_len);
void tianboardDataProc(unsigned char *buf, int len);
void heartCallback();
void communicationErrorCallback();
// new function
void initSub();
void initPub();
void heartBeatTimer(const std::chrono::milliseconds timeout);
void communicationTimer(const std::chrono::milliseconds timeout);
void run();
};

#endif
38 changes: 38 additions & 0 deletions tianracer_core/launch/tianracer_core.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument


def generate_launch_description():
pkg_share = get_package_share_directory("tianracer_core")

serial_port = LaunchConfiguration("serial_port_core", \
default=os.environ.get("TIANRACER_BASE_PORT", "/dev/tianbot_racecar"))

tianracer_core = Node(
package='tianracer_core',
node_executable='tianracer_core_node',
name='tianracer',
output='screen',
parameters=[{'serial_port': serial_port}])

robot_localization_node = Node(
package='robot_localization',
node_executable='ekf_node',
name='ekf_filter_node',
output='screen',
parameters=[os.path.join(pkg_share, 'param/tianbot_ekf_params.yaml')]
)

return LaunchDescription([
DeclareLaunchArgument(
'serial_port_core',
default_value=serial_port,
description='Tianracer base port'),
tianracer_core,
robot_localization_node

])
Loading

0 comments on commit 6815d03

Please sign in to comment.