Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
117 changes: 117 additions & 0 deletions rm_vt/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
cmake_minimum_required(VERSION 3.0.2)
project(rm_vt)

## Use C++14
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

## By adding -Wall and -Werror, the compiler does not ignore warnings anymore,
## enforcing cleaner code.
add_definitions(-Wall -Werror -Wno-address-of-packed-member)

## Find catkin macros and libraries
find_package(serial REQUIRED)

find_package(catkin REQUIRED
COMPONENTS
sensor_msgs
roscpp
rm_msgs
serial
rm_common
tf2_geometry_msgs
std_msgs
actionlib
nav_msgs
)

## Find system libraries
#find_package(Eigen3 REQUIRED)

###################################
## 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
CATKIN_DEPENDS
roscpp
sensor_msgs
rm_msgs
rm_common
tf2_geometry_msgs
std_msgs
actionlib
nav_msgs
DEPENDS
)

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

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

## Declare cpp executables
FILE(GLOB ALL_SOURCES "src/*.cpp" "src/common/*.cpp" )
add_executable(${PROJECT_NAME} ${ALL_SOURCES})

## Add dependencies to exported targets, like ROS msgs or srvs
add_dependencies(${PROJECT_NAME}
${catkin_EXPORTED_TARGETS}
)

## Specify libraries to link executable targets against
target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
)

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

# Mark executables and/or libraries for installation
install(
TARGETS ${PROJECT_NAME}
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"
)

## Mark other files for installation
install(
DIRECTORY launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

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

#if (${CATKIN_ENABLE_TESTING})
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread")
# ## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test
# test/test_ros_package_template.cpp
# test/AlgorithmTest.cpp)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}_core)
#endif ()
113 changes: 113 additions & 0 deletions rm_vt/include/rm_vt/common/data.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
//
// Created by chen on 24-11-23.
//

#pragma once

#include <ros/ros.h>
#include <unistd.h>
#include <serial/serial.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/JointState.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Int8MultiArray.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include "std_msgs/UInt32.h"
#include "std_msgs/Float64MultiArray.h"
#include "rm_msgs/VisualizeStateData.h"

#include "rm_vt/common/protocol.h"

namespace rm_vt
{
class Base
{
public:
serial::Serial serial_;
bool video_tran_is_online_ = false;

void initSerial()
{
serial::Timeout timeout = serial::Timeout::simpleTimeout(50);
serial_.setPort("/dev/usbImagetran");
serial_.setBaudrate(115200);
serial_.setTimeout(timeout);
if (serial_.isOpen())
return;
try
{
serial_.open();
}
catch (serial::IOException& e)
{
ROS_ERROR("Cannot open image transmitter port");
}
}

// CRC check
uint8_t getCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length, unsigned char uc_crc_8)
{
unsigned char uc_index;
while (dw_length--)
{
uc_index = uc_crc_8 ^ (*pch_message++);
uc_crc_8 = rm_vt::kCrc8Table[uc_index];
}
return (uc_crc_8);
}

uint32_t verifyCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
{
unsigned char uc_expected;
if ((pch_message == nullptr) || (dw_length <= 2))
return 0;
uc_expected = getCRC8CheckSum(pch_message, dw_length - 1, rm_vt::kCrc8Init);
return (uc_expected == pch_message[dw_length - 1]);
}

void appendCRC8CheckSum(unsigned char* pch_message, unsigned int dw_length)
{
unsigned char uc_crc;
if ((pch_message == nullptr) || (dw_length <= 2))
return;
uc_crc = getCRC8CheckSum((unsigned char*)pch_message, dw_length - 1, rm_vt::kCrc8Init);
pch_message[dw_length - 1] = uc_crc;
}

uint16_t getCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length, uint16_t w_crc)
{
uint8_t chData;
if (pch_message == nullptr)
return 0xFFFF;
while (dw_length--)
{
chData = *pch_message++;
(w_crc) = (static_cast<uint16_t>(w_crc) >> 8) ^
rm_vt::wCRC_table[(static_cast<uint16_t>(w_crc) ^ static_cast<uint16_t>(chData)) & 0x00ff];
}
return w_crc;
}

uint32_t verifyCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
{
uint16_t w_expected;
if ((pch_message == nullptr) || (dw_length <= 2))
return 0;
w_expected = getCRC16CheckSum(pch_message, dw_length - 2, rm_vt::kCrc16Init);
return ((w_expected & 0xff) == pch_message[dw_length - 2] &&
((w_expected >> 8) & 0xff) == pch_message[dw_length - 1]);
}

void appendCRC16CheckSum(uint8_t* pch_message, uint32_t dw_length)
{
uint16_t wCRC;
if ((pch_message == nullptr) || (dw_length <= 2))
return;
wCRC = getCRC16CheckSum(static_cast<uint8_t*>(pch_message), dw_length - 2, rm_vt::kCrc16Init);
pch_message[dw_length - 2] = static_cast<uint8_t>((wCRC & 0x00ff));
pch_message[dw_length - 1] = static_cast<uint8_t>(((wCRC >> 8) & 0x00ff));
}
};
} // namespace rm_vt
103 changes: 103 additions & 0 deletions rm_vt/include/rm_vt/common/protocol.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
//
// Created by chen on 24-11-23.
//
#pragma once
#define __packed __attribute__((packed))

#include <cstdint>
namespace rm_vt
{
typedef enum
{
GAME_STATUS_CMD = 0x0001,
GAME_RESULT_CMD = 0x0002,
GAME_ROBOT_HP_CMD = 0x0003,
DART_STATUS_CMD = 0x0004,
ICRA_ZONE_STATUS_CMD = 0x0005,
FIELD_EVENTS_CMD = 0x0101,
SUPPLY_PROJECTILE_ACTION_CMD = 0x0102,
REFEREE_WARNING_CMD = 0x0104,
DART_REMAINING_CMD = 0x0105,
ROBOT_STATUS_CMD = 0x0201,
POWER_HEAT_DATA_CMD = 0x0202,
ROBOT_POS_CMD = 0x0203,
BUFF_CMD = 0x0204,
AERIAL_ROBOT_ENERGY_CMD = 0x0205,
ROBOT_HURT_CMD = 0x0206,
SHOOT_DATA_CMD = 0x0207,
BULLET_REMAINING_CMD = 0x0208,
ROBOT_RFID_STATUS_CMD = 0x0209,
DART_CLIENT_CMD = 0x020A,
ROBOTS_POS_CMD = 0X020B,
RADAR_MARK_CMD = 0X020C,
SENTRY_INFO_CMD = 0x020D,
RADAR_INFO_CMD = 0x020E,
INTERACTIVE_DATA_CMD = 0x0301,
CUSTOM_CONTROLLER_CMD = 0x0302, // controller
TARGET_POS_CMD = 0x0303,
ROBOT_COMMAND_CMD = 0x0304, // controller
CLIENT_MAP_CMD = 0x0305,
CUSTOM_CLIENT_CMD = 0x0306, // controller
MAP_SENTRY_CMD = 0x0307, // send sentry->aerial
CUSTOM_INFO_CMD = 0x0308,
POWER_MANAGEMENT_SAMPLE_AND_STATUS_DATA_CMD = 0X8301,
POWER_MANAGEMENT_INITIALIZATION_EXCEPTION_CMD = 0X8302,
POWER_MANAGEMENT_SYSTEM_EXCEPTION_CMD = 0X8303,
POWER_MANAGEMENT_PROCESS_STACK_OVERFLOW_CMD = 0X8304,
POWER_MANAGEMENT_UNKNOWN_EXCEPTION_CMD = 0X8305
} RefereeCmdId;

typedef struct
{
uint8_t sof;
uint16_t data_length;
uint8_t seq;
uint8_t crc_8;
} __packed FrameHeader;

typedef struct
{
uint8_t data[30];
} __packed CustomControllerData;

/***********************Frame tail(CRC8_CRC16)********************************************/
const uint8_t kCrc8Init = 0xff;
const uint8_t kCrc8Table[256] = {
0x00, 0x5e, 0xbc, 0xe2, 0x61, 0x3f, 0xdd, 0x83, 0xc2, 0x9c, 0x7e, 0x20, 0xa3, 0xfd, 0x1f, 0x41, 0x9d, 0xc3, 0x21,
0x7f, 0xfc, 0xa2, 0x40, 0x1e, 0x5f, 0x01, 0xe3, 0xbd, 0x3e, 0x60, 0x82, 0xdc, 0x23, 0x7d, 0x9f, 0xc1, 0x42, 0x1c,
0xfe, 0xa0, 0xe1, 0xbf, 0x5d, 0x03, 0x80, 0xde, 0x3c, 0x62, 0xbe, 0xe0, 0x02, 0x5c, 0xdf, 0x81, 0x63, 0x3d, 0x7c,
0x22, 0xc0, 0x9e, 0x1d, 0x43, 0xa1, 0xff, 0x46, 0x18, 0xfa, 0xa4, 0x27, 0x79, 0x9b, 0xc5, 0x84, 0xda, 0x38, 0x66,
0xe5, 0xbb, 0x59, 0x07, 0xdb, 0x85, 0x67, 0x39, 0xba, 0xe4, 0x06, 0x58, 0x19, 0x47, 0xa5, 0xfb, 0x78, 0x26, 0xc4,
0x9a, 0x65, 0x3b, 0xd9, 0x87, 0x04, 0x5a, 0xb8, 0xe6, 0xa7, 0xf9, 0x1b, 0x45, 0xc6, 0x98, 0x7a, 0x24, 0xf8, 0xa6,
0x44, 0x1a, 0x99, 0xc7, 0x25, 0x7b, 0x3a, 0x64, 0x86, 0xd8, 0x5b, 0x05, 0xe7, 0xb9, 0x8c, 0xd2, 0x30, 0x6e, 0xed,
0xb3, 0x51, 0x0f, 0x4e, 0x10, 0xf2, 0xac, 0x2f, 0x71, 0x93, 0xcd, 0x11, 0x4f, 0xad, 0xf3, 0x70, 0x2e, 0xcc, 0x92,
0xd3, 0x8d, 0x6f, 0x31, 0xb2, 0xec, 0x0e, 0x50, 0xaf, 0xf1, 0x13, 0x4d, 0xce, 0x90, 0x72, 0x2c, 0x6d, 0x33, 0xd1,
0x8f, 0x0c, 0x52, 0xb0, 0xee, 0x32, 0x6c, 0x8e, 0xd0, 0x53, 0x0d, 0xef, 0xb1, 0xf0, 0xae, 0x4c, 0x12, 0x91, 0xcf,
0x2d, 0x73, 0xca, 0x94, 0x76, 0x28, 0xab, 0xf5, 0x17, 0x49, 0x08, 0x56, 0xb4, 0xea, 0x69, 0x37, 0xd5, 0x8b, 0x57,
0x09, 0xeb, 0xb5, 0x36, 0x68, 0x8a, 0xd4, 0x95, 0xcb, 0x29, 0x77, 0xf4, 0xaa, 0x48, 0x16, 0xe9, 0xb7, 0x55, 0x0b,
0x88, 0xd6, 0x34, 0x6a, 0x2b, 0x75, 0x97, 0xc9, 0x4a, 0x14, 0xf6, 0xa8, 0x74, 0x2a, 0xc8, 0x96, 0x15, 0x4b, 0xa9,
0xf7, 0xb6, 0xe8, 0x0a, 0x54, 0xd7, 0x89, 0x6b, 0x35,
};
const uint16_t kCrc16Init = 0xffff;
const uint16_t wCRC_table[256] = {
0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5,
0xe97e, 0xf8f7, 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, 0x9cc9, 0x8d40, 0xbfdb, 0xae52,
0xdaed, 0xcb64, 0xf9ff, 0xe876, 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, 0xad4a, 0xbcc3,
0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c,
0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9,
0x2732, 0x36bb, 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, 0x5285, 0x430c, 0x7197, 0x601e,
0x14a1, 0x0528, 0x37b3, 0x263a, 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, 0x6306, 0x728f,
0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1,
0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862,
0x9af9, 0x8b70, 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, 0x0840, 0x19c9, 0x2b52, 0x3adb,
0x4e64, 0x5fed, 0x6d76, 0x7cff, 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, 0x18c1, 0x0948,
0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5,
0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226,
0xd0bd, 0xc134, 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, 0xc60c, 0xd785, 0xe51e, 0xf497,
0x8028, 0x91a1, 0xa33a, 0xb2b3, 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, 0xd68d, 0xc704,
0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a,
0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb,
0x0e70, 0x1ff9, 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, 0x7bc7, 0x6a4e, 0x58d5, 0x495c,
0x3de3, 0x2c6a, 0x1ef1, 0x0f78
};
} // namespace rm_vt
42 changes: 42 additions & 0 deletions rm_vt/include/rm_vt/video_tran.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
//
// Created by chen on 24-11-23.
//
#pragma once

#include <cstdint>
#include <ros/ros.h>

#include "rm_vt/common/data.h"

namespace rm_vt
{
class VideoTran
{
public:
explicit VideoTran(ros::NodeHandle& nh) : last_get_data_time_(ros::Time::now())
{
ROS_INFO("Video transmission load.");
custom_controller_cmd_pub_ = nh.advertise<std_msgs::Float64MultiArray>("custom_controller_data", 1);
base_.initSerial();
}
void read();
void clearRxBuffer()
{
rx_buffer_.clear();
rx_len_ = 0;
}

ros::Publisher custom_controller_cmd_pub_;

Base base_;
std::vector<uint8_t> rx_buffer_;
int rx_len_;

private:
int unpack(uint8_t* rx_data);
ros::Time last_get_data_time_;
const int k_frame_length_ = 128, k_header_length_ = 5, k_cmd_id_length_ = 2, k_tail_length_ = 2;
const int k_unpack_buffer_length_ = 256;
uint8_t unpack_buffer_[256]{};
};
} // namespace rm_vt
6 changes: 6 additions & 0 deletions rm_vt/launch/load.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<launch>
<arg name="robot_type" default="$(env ROBOT_TYPE)" doc="Robot type [standard, hero, engineer]"/>

<node name="rm_vt" pkg="rm_vt" type="rm_vt" respawn="false"/>

</launch>
Loading
Loading