mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 03:15:01 +08:00
init commit
This commit is contained in:
101
scout_base/.gitignore
vendored
Normal file
101
scout_base/.gitignore
vendored
Normal file
@@ -0,0 +1,101 @@
|
|||||||
|
# build
|
||||||
|
*/Debug
|
||||||
|
build
|
||||||
|
*/build
|
||||||
|
cmake-build-debug
|
||||||
|
cmake-build-release/
|
||||||
|
|
||||||
|
# Temp files
|
||||||
|
*~
|
||||||
|
*/~
|
||||||
|
*/*.*~
|
||||||
|
*.m~
|
||||||
|
*.DS_Store
|
||||||
|
|
||||||
|
# log
|
||||||
|
*.log
|
||||||
|
#*.data
|
||||||
|
|
||||||
|
# Doxygen
|
||||||
|
docs/doxygen/html/
|
||||||
|
docs/doxygen/latex
|
||||||
|
|
||||||
|
# Qt Creator
|
||||||
|
pc/visualization/CMakeLists.txt.user
|
||||||
|
|
||||||
|
# VS Code
|
||||||
|
.vscode
|
||||||
|
|
||||||
|
# CLion
|
||||||
|
.idea/
|
||||||
|
|
||||||
|
# LCM
|
||||||
|
src/lcmtypes/c
|
||||||
|
src/lcmtypes/cpp
|
||||||
|
src/lcmtypes/java
|
||||||
|
src/lcmtypes/python
|
||||||
|
|
||||||
|
# Compiled Object files
|
||||||
|
*.slo
|
||||||
|
*.lo
|
||||||
|
*.o
|
||||||
|
*.obj
|
||||||
|
|
||||||
|
# Precompiled Headers
|
||||||
|
*.gch
|
||||||
|
*.pch
|
||||||
|
|
||||||
|
# Compiled Dynamic libraries
|
||||||
|
#*.so
|
||||||
|
#*.dylib
|
||||||
|
#*.dll
|
||||||
|
|
||||||
|
# Fortran module files
|
||||||
|
*.mod
|
||||||
|
|
||||||
|
# Compiled Static libraries
|
||||||
|
#*.lai
|
||||||
|
#*.la
|
||||||
|
#*.a
|
||||||
|
#*.lib
|
||||||
|
|
||||||
|
# Executables
|
||||||
|
*.exe
|
||||||
|
*.out
|
||||||
|
*.app
|
||||||
|
|
||||||
|
# Vim
|
||||||
|
tags
|
||||||
|
*/tags
|
||||||
|
*.swp
|
||||||
|
*/*.swp
|
||||||
|
|
||||||
|
# vscode
|
||||||
|
.vscode
|
||||||
|
|
||||||
|
# Python
|
||||||
|
*.pyc
|
||||||
|
__pycache__
|
||||||
|
|
||||||
|
##---------------------------------------------------
|
||||||
|
## Remove autosaves generated by the Matlab editor
|
||||||
|
## We have git for backups!
|
||||||
|
##---------------------------------------------------
|
||||||
|
|
||||||
|
# Windows default autosave extension
|
||||||
|
*.asv
|
||||||
|
|
||||||
|
# OSX / *nix default autosave extension
|
||||||
|
*.m~
|
||||||
|
|
||||||
|
# Compiled MEX binaries (all platforms)
|
||||||
|
*.mex*
|
||||||
|
|
||||||
|
# Simulink Code Generation
|
||||||
|
slprj/
|
||||||
|
|
||||||
|
# Session info
|
||||||
|
octave-workspace
|
||||||
|
|
||||||
|
# Simulink autosave extension
|
||||||
|
.autosave
|
||||||
143
scout_base/CMakeLists.txt
Normal file
143
scout_base/CMakeLists.txt
Normal file
@@ -0,0 +1,143 @@
|
|||||||
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
|
project(scout_base)
|
||||||
|
|
||||||
|
## 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
|
||||||
|
geometry_msgs
|
||||||
|
roscpp
|
||||||
|
rospy
|
||||||
|
std_msgs
|
||||||
|
tf
|
||||||
|
)
|
||||||
|
|
||||||
|
## 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 ##
|
||||||
|
################################################
|
||||||
|
|
||||||
|
## Generate messages in the 'msg' folder
|
||||||
|
add_message_files(
|
||||||
|
FILES
|
||||||
|
Encode.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 # std_msgs
|
||||||
|
)
|
||||||
|
|
||||||
|
################################################
|
||||||
|
## Declare ROS dynamic reconfigure parameters ##
|
||||||
|
################################################
|
||||||
|
|
||||||
|
## Generate dynamic reconfigure parameters in the 'cfg' folder
|
||||||
|
# generate_dynamic_reconfigure_options(
|
||||||
|
# cfg/DynReconf1.cfg
|
||||||
|
# cfg/DynReconf2.cfg
|
||||||
|
# )
|
||||||
|
|
||||||
|
###################################
|
||||||
|
## catkin specific configuration ##
|
||||||
|
###################################
|
||||||
|
|
||||||
|
catkin_package(
|
||||||
|
INCLUDE_DIRS include
|
||||||
|
# LIBRARIES scout_base
|
||||||
|
CATKIN_DEPENDS message_runtime geometry_msgs roscpp rospy std_msgs tf
|
||||||
|
# DEPENDS system_lib
|
||||||
|
)
|
||||||
|
|
||||||
|
###########
|
||||||
|
## Build ##
|
||||||
|
###########
|
||||||
|
|
||||||
|
## Specify additional locations of header files
|
||||||
|
## Your package locations should be listed before other locations
|
||||||
|
include_directories(
|
||||||
|
include
|
||||||
|
${catkin_INCLUDE_DIRS}
|
||||||
|
)
|
||||||
|
|
||||||
|
# add scout sdk
|
||||||
|
add_subdirectory(src/scout_sdk)
|
||||||
|
|
||||||
|
add_executable(scout_ros src/scout_ros.cpp)
|
||||||
|
target_link_libraries(scout_ros scoutcpp ${catkin_LIBRARIES})
|
||||||
|
|
||||||
|
add_executable(keybord src/keybord.cpp)
|
||||||
|
target_link_libraries(keybord ${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_scout_base.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)
|
||||||
16
scout_base/README.md
Normal file
16
scout_base/README.md
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
# Prerequisites
|
||||||
|
|
||||||
|
* Make sure your user account has access to
|
||||||
|
* serial port (to communicate with robot base)
|
||||||
|
* keyboard input (to use keyboard control)
|
||||||
|
|
||||||
|
* Grant access to serial port
|
||||||
|
```
|
||||||
|
# Note: you can use "ls /dev/ttyUSB*" to check the serial port number on your computer
|
||||||
|
$ sudo chmod 666 /dev/ttyUSB0
|
||||||
|
```
|
||||||
|
|
||||||
|
* Add user to "input" group
|
||||||
|
```
|
||||||
|
$ sudo adduser <your-user-name> input
|
||||||
|
```
|
||||||
14
scout_base/launch/keybord.launch
Normal file
14
scout_base/launch/keybord.launch
Normal file
@@ -0,0 +1,14 @@
|
|||||||
|
<launch>
|
||||||
|
<node name="keybord" pkg="scout_base" type="keybord" output="screen">
|
||||||
|
|
||||||
|
<param name="input" value="/dev/input/event3" />
|
||||||
|
|
||||||
|
<param name="walk_vel" value="0.5" />
|
||||||
|
<param name="run_vel" value="0.5" />
|
||||||
|
|
||||||
|
<param name="max_tv" value="2.0" />
|
||||||
|
<param name="max_rv" value="2.6" />
|
||||||
|
|
||||||
|
</node>
|
||||||
|
|
||||||
|
</launch>
|
||||||
15
scout_base/launch/scout_base.launch
Normal file
15
scout_base/launch/scout_base.launch
Normal file
@@ -0,0 +1,15 @@
|
|||||||
|
<launch>
|
||||||
|
|
||||||
|
<node name="scout_odom" pkg="scout_base" type="scout_ros" output="screen">
|
||||||
|
|
||||||
|
<param name="port_name" type="string" value="/dev/ttyUSB0" />
|
||||||
|
<param name="baud_rate" value="115200" />
|
||||||
|
|
||||||
|
<param name="odom_frame" type="string" value="odom" />
|
||||||
|
<param name="base_frame" type="string" value="base_footprint" />
|
||||||
|
|
||||||
|
<param name="control_rate" value="10" />
|
||||||
|
|
||||||
|
</node>
|
||||||
|
|
||||||
|
</launch>
|
||||||
2
scout_base/msg/Encode.msg
Normal file
2
scout_base/msg/Encode.msg
Normal file
@@ -0,0 +1,2 @@
|
|||||||
|
int64 left
|
||||||
|
int64 right
|
||||||
76
scout_base/package.xml
Normal file
76
scout_base/package.xml
Normal file
@@ -0,0 +1,76 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<package format="2">
|
||||||
|
<name>scout_base</name>
|
||||||
|
<version>0.0.0</version>
|
||||||
|
<description>The scout_base package</description>
|
||||||
|
|
||||||
|
<!-- One maintainer tag required, multiple allowed, one person per tag -->
|
||||||
|
<!-- Example: -->
|
||||||
|
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
|
||||||
|
<maintainer email="rdu@todo.todo">rdu</maintainer>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- One license tag required, multiple allowed, one license per tag -->
|
||||||
|
<!-- Commonly used license strings: -->
|
||||||
|
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
||||||
|
<license>TODO</license>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- Url tags are optional, but multiple are allowed, one per tag -->
|
||||||
|
<!-- Optional attribute type can be: website, bugtracker, or repository -->
|
||||||
|
<!-- Example: -->
|
||||||
|
<!-- <url type="website">http://wiki.ros.org/scout_base</url> -->
|
||||||
|
|
||||||
|
|
||||||
|
<!-- Author tags are optional, multiple are allowed, one per tag -->
|
||||||
|
<!-- Authors do not have to be maintainers, but could be -->
|
||||||
|
<!-- Example: -->
|
||||||
|
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
|
||||||
|
|
||||||
|
|
||||||
|
<!-- The *depend tags are used to specify dependencies -->
|
||||||
|
<!-- Dependencies can be catkin packages or system dependencies -->
|
||||||
|
<!-- Examples: -->
|
||||||
|
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
|
||||||
|
<!-- <depend>roscpp</depend> -->
|
||||||
|
<!-- Note that this is equivalent to the following: -->
|
||||||
|
<!-- <build_depend>roscpp</build_depend> -->
|
||||||
|
<!-- <exec_depend>roscpp</exec_depend> -->
|
||||||
|
<!-- Use build_depend for packages you need at compile time: -->
|
||||||
|
<!-- <build_depend>message_generation</build_depend> -->
|
||||||
|
<!-- Use build_export_depend for packages you need in order to build against this package: -->
|
||||||
|
<!-- <build_export_depend>message_generation</build_export_depend> -->
|
||||||
|
<!-- Use buildtool_depend for build tool packages: -->
|
||||||
|
<!-- <buildtool_depend>catkin</buildtool_depend> -->
|
||||||
|
<!-- Use exec_depend for packages you need at runtime: -->
|
||||||
|
<!-- <exec_depend>message_runtime</exec_depend> -->
|
||||||
|
<!-- Use test_depend for packages you need only for testing: -->
|
||||||
|
<!-- <test_depend>gtest</test_depend> -->
|
||||||
|
<!-- Use doc_depend for packages you need only for building documentation: -->
|
||||||
|
<!-- <doc_depend>doxygen</doc_depend> -->
|
||||||
|
<buildtool_depend>catkin</buildtool_depend>
|
||||||
|
<build_depend>geometry_msgs</build_depend>
|
||||||
|
<build_depend>roscpp</build_depend>
|
||||||
|
<build_depend>rospy</build_depend>
|
||||||
|
<build_depend>std_msgs</build_depend>
|
||||||
|
<build_depend>tf</build_depend>
|
||||||
|
<build_depend>message_generation</build_depend>
|
||||||
|
<build_export_depend>geometry_msgs</build_export_depend>
|
||||||
|
<build_export_depend>roscpp</build_export_depend>
|
||||||
|
<build_export_depend>rospy</build_export_depend>
|
||||||
|
<build_export_depend>std_msgs</build_export_depend>
|
||||||
|
<build_export_depend>tf</build_export_depend>
|
||||||
|
<exec_depend>message_runtime</exec_depend>
|
||||||
|
<exec_depend>geometry_msgs</exec_depend>
|
||||||
|
<exec_depend>roscpp</exec_depend>
|
||||||
|
<exec_depend>rospy</exec_depend>
|
||||||
|
<exec_depend>std_msgs</exec_depend>
|
||||||
|
<exec_depend>tf</exec_depend>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
|
<export>
|
||||||
|
<!-- Other tools can request additional information be placed here -->
|
||||||
|
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
203
scout_base/src/keybord.cpp
Normal file
203
scout_base/src/keybord.cpp
Normal file
@@ -0,0 +1,203 @@
|
|||||||
|
#include <termios.h>
|
||||||
|
#include <signal.h>
|
||||||
|
#include <math.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <sys/poll.h>
|
||||||
|
#include <boost/thread/thread.hpp>
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <geometry_msgs/Twist.h>
|
||||||
|
#include <linux/input.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
|
||||||
|
#define KEY_W 17
|
||||||
|
#define KEY_A 30
|
||||||
|
#define KEY_S 31
|
||||||
|
#define KEY_D 32
|
||||||
|
#define KEY_UP 103
|
||||||
|
#define KEY_LEFT 105
|
||||||
|
#define KEY_DOWN 108
|
||||||
|
#define KEY_RIGHT 106
|
||||||
|
|
||||||
|
#define DEBUG 0
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
class Keyboard
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
double walk_vel_;
|
||||||
|
double run_vel_;
|
||||||
|
double max_tv;
|
||||||
|
double max_rv;
|
||||||
|
std::string input;
|
||||||
|
|
||||||
|
int kfd;
|
||||||
|
struct termios cooked, raw;
|
||||||
|
struct input_event t;
|
||||||
|
|
||||||
|
geometry_msgs::Twist cmdvel_;
|
||||||
|
ros::NodeHandle n_;
|
||||||
|
ros::Publisher pub_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
Keyboard()
|
||||||
|
{
|
||||||
|
pub_ = n_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
|
||||||
|
ros::NodeHandle n_private("~");
|
||||||
|
n_private.param("walk_vel", walk_vel_, 0.5);
|
||||||
|
n_private.param("run_vel", run_vel_, 0.5);
|
||||||
|
n_private.param("max_tv", max_tv, 2.0);
|
||||||
|
n_private.param("max_rv", max_rv, 2.6);
|
||||||
|
n_private.param("input", input, std::string("/dev/input/event3"));
|
||||||
|
|
||||||
|
Hidden_Character();
|
||||||
|
}
|
||||||
|
~Keyboard()
|
||||||
|
{
|
||||||
|
tcsetattr(kfd, TCSANOW, &cooked); //恢复参数
|
||||||
|
}
|
||||||
|
|
||||||
|
void keyboardLoop();
|
||||||
|
void stopRobot()
|
||||||
|
{
|
||||||
|
cmdvel_.linear.x = 0.0;
|
||||||
|
cmdvel_.angular.z = 0.0;
|
||||||
|
pub_.publish(cmdvel_);
|
||||||
|
}
|
||||||
|
void Hidden_Character()
|
||||||
|
{
|
||||||
|
//隐藏字符
|
||||||
|
tcgetattr(kfd, &cooked);
|
||||||
|
memcpy(&raw, &cooked, sizeof(struct termios));
|
||||||
|
raw.c_lflag &= ~(ICANON | ECHO);
|
||||||
|
raw.c_cc[VEOL] = 1;
|
||||||
|
raw.c_cc[VEOF] = 2;
|
||||||
|
tcsetattr(kfd, TCSANOW, &raw);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
string msg = "\n\
|
||||||
|
Reading from the keyboard and Publishing to Twist!\n\
|
||||||
|
---------------------------\n\
|
||||||
|
Moving around:\n\
|
||||||
|
\n\
|
||||||
|
w \n\
|
||||||
|
a s d \n\
|
||||||
|
\n\
|
||||||
|
UP/DOWN : increase/decrease only linear speed by 0.2\n\
|
||||||
|
LEFT/RIGHT : increase/decrease only angular speed by 0.2\n\
|
||||||
|
CTRL-C to quit";
|
||||||
|
|
||||||
|
void Keyboard::keyboardLoop()
|
||||||
|
{
|
||||||
|
char c;
|
||||||
|
int speed = 0, turn = 0;
|
||||||
|
int keys_fd;
|
||||||
|
char ret[2];
|
||||||
|
|
||||||
|
ROS_INFO_STREAM(msg);
|
||||||
|
|
||||||
|
keys_fd = open(input.c_str(), O_RDONLY);
|
||||||
|
if (keys_fd <= 0)
|
||||||
|
{
|
||||||
|
ROS_INFO_STREAM("open " << input << " device error");
|
||||||
|
}
|
||||||
|
|
||||||
|
for (;;)
|
||||||
|
{
|
||||||
|
if (read(keys_fd, &t, sizeof(t)) == sizeof(t))
|
||||||
|
{
|
||||||
|
if (t.type == EV_KEY)
|
||||||
|
{
|
||||||
|
if (t.value == 0 || t.value == 1)
|
||||||
|
{
|
||||||
|
#if DEBUG
|
||||||
|
printf("key %d %d\n", t.code, t.value);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (t.code == KEY_W)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
speed = 1;
|
||||||
|
else
|
||||||
|
speed = 0;
|
||||||
|
}
|
||||||
|
else if (t.code == KEY_S)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
speed = -1;
|
||||||
|
else
|
||||||
|
speed = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t.code == KEY_A)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
turn = -1;
|
||||||
|
else
|
||||||
|
turn = 0;
|
||||||
|
}
|
||||||
|
else if (t.code == KEY_D)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
turn = 1;
|
||||||
|
else
|
||||||
|
turn = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t.code == KEY_UP)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
{
|
||||||
|
max_tv += 0.2;
|
||||||
|
if (max_tv > 2)
|
||||||
|
max_tv = 2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (t.code == KEY_DOWN)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
{
|
||||||
|
max_tv -= 0.2;
|
||||||
|
if (max_tv < 0.2)
|
||||||
|
max_tv = 0.2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (t.code == KEY_LEFT)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
{
|
||||||
|
max_rv -= 0.2;
|
||||||
|
if (max_rv < 0.2)
|
||||||
|
max_rv = 0.2;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (t.code == KEY_RIGHT)
|
||||||
|
{
|
||||||
|
if (t.value == 1)
|
||||||
|
{
|
||||||
|
max_rv += 0.2;
|
||||||
|
if (max_rv > 3)
|
||||||
|
max_rv = 3;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
cmdvel_.linear.x = speed * max_tv;
|
||||||
|
cmdvel_.angular.z = turn * max_rv;
|
||||||
|
pub_.publish(cmdvel_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
close(keys_fd);
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "keybord");
|
||||||
|
Keyboard tbk;
|
||||||
|
boost::thread t = boost::thread(boost::bind(&Keyboard::keyboardLoop, &tbk));
|
||||||
|
ros::spin();
|
||||||
|
return (0);
|
||||||
|
}
|
||||||
197
scout_base/src/scout_ros.cpp
Normal file
197
scout_base/src/scout_ros.cpp
Normal file
@@ -0,0 +1,197 @@
|
|||||||
|
#include <string>
|
||||||
|
#include <boost/thread.hpp>
|
||||||
|
|
||||||
|
#include <ros/ros.h>
|
||||||
|
#include <sensor_msgs/JointState.h>
|
||||||
|
#include <tf/transform_broadcaster.h>
|
||||||
|
#include <nav_msgs/Odometry.h>
|
||||||
|
|
||||||
|
#include "scout/scout_robot.h"
|
||||||
|
|
||||||
|
#define Send_Speed_Debug 0
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace scout;
|
||||||
|
|
||||||
|
class ScoutROSMessenger
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
void run(void);
|
||||||
|
|
||||||
|
void TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg);
|
||||||
|
void SendSpeedCmdCallback(const ros::TimerEvent &);
|
||||||
|
void PublishOdometry(void);
|
||||||
|
|
||||||
|
private:
|
||||||
|
ScoutRobot robot_;
|
||||||
|
|
||||||
|
boost::mutex twist_mutex_;
|
||||||
|
geometry_msgs::Twist current_twist_;
|
||||||
|
ros::Publisher odom_publisher_;
|
||||||
|
tf::TransformBroadcaster tf_broadcaster_;
|
||||||
|
|
||||||
|
std::string odom_frame_;
|
||||||
|
std::string base_frame_;
|
||||||
|
|
||||||
|
int ctrl_rate_;
|
||||||
|
std::string port_name_;
|
||||||
|
int baud_rate_;
|
||||||
|
|
||||||
|
double x;
|
||||||
|
double y;
|
||||||
|
double th;
|
||||||
|
double vx;
|
||||||
|
double vy;
|
||||||
|
double vth;
|
||||||
|
|
||||||
|
ros::Time last_time_;
|
||||||
|
ros::Time current_time_;
|
||||||
|
|
||||||
|
void PublishStateToROS(short linear, short angular);
|
||||||
|
void SendCmdToRobot(geometry_msgs::Twist *current_twist_);
|
||||||
|
};
|
||||||
|
|
||||||
|
void ScoutROSMessenger::TwistCmdCallback(const geometry_msgs::Twist::ConstPtr &msg)
|
||||||
|
{
|
||||||
|
twist_mutex_.lock();
|
||||||
|
current_twist_ = *msg.get();
|
||||||
|
twist_mutex_.unlock();
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::SendSpeedCmdCallback(const ros::TimerEvent &)
|
||||||
|
{
|
||||||
|
SendCmdToRobot(¤t_twist_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::PublishOdometry(void)
|
||||||
|
{
|
||||||
|
RobotState data;
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
if (robot_.QueryRobotState(&data))
|
||||||
|
PublishStateToROS(data.linear, data.angular);
|
||||||
|
boost::this_thread::sleep(boost::posix_time::milliseconds(5));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::PublishStateToROS(short linear, short angular)
|
||||||
|
{
|
||||||
|
current_time_ = ros::Time::now();
|
||||||
|
double dt = (current_time_ - last_time_).toSec();
|
||||||
|
|
||||||
|
static bool init_run = true;
|
||||||
|
if (init_run)
|
||||||
|
{
|
||||||
|
last_time_ = current_time_;
|
||||||
|
init_run = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
double Angular = angular;
|
||||||
|
double Linear = linear;
|
||||||
|
Angular /= 10000;
|
||||||
|
Linear /= 10000;
|
||||||
|
|
||||||
|
vth = Angular; //旋转角速度,在角度很小的情况下。约等于(SPEED右 - SPEED左)/ 轮子间距
|
||||||
|
vx = Linear; //直线X轴的速度 = (SPEED右 - SPEED左) / 2
|
||||||
|
vy = 0.0; //2轮差速车,不能左右横移
|
||||||
|
|
||||||
|
double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
|
||||||
|
double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
|
||||||
|
double delta_th = vth * dt;
|
||||||
|
|
||||||
|
x += delta_x;
|
||||||
|
y += delta_y;
|
||||||
|
th += delta_th;
|
||||||
|
|
||||||
|
//since all odometry is 6DOF we'll need a quaternion created from yaw
|
||||||
|
geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
|
||||||
|
|
||||||
|
//first, we'll publish the transform over tf
|
||||||
|
geometry_msgs::TransformStamped odom_trans;
|
||||||
|
odom_trans.header.stamp = current_time_;
|
||||||
|
odom_trans.header.frame_id = odom_frame_;
|
||||||
|
odom_trans.child_frame_id = base_frame_;
|
||||||
|
|
||||||
|
odom_trans.transform.translation.x = x;
|
||||||
|
odom_trans.transform.translation.y = y;
|
||||||
|
odom_trans.transform.translation.z = 0.0;
|
||||||
|
odom_trans.transform.rotation = odom_quat;
|
||||||
|
|
||||||
|
//send the transform
|
||||||
|
tf_broadcaster_.sendTransform(odom_trans);
|
||||||
|
|
||||||
|
//next, we'll publish the odometry message over ROS
|
||||||
|
nav_msgs::Odometry odom;
|
||||||
|
odom.header.stamp = current_time_;
|
||||||
|
odom.header.frame_id = odom_frame_;
|
||||||
|
odom.child_frame_id = base_frame_;
|
||||||
|
|
||||||
|
//set the position
|
||||||
|
odom.pose.pose.position.x = x;
|
||||||
|
odom.pose.pose.position.y = y;
|
||||||
|
odom.pose.pose.position.z = 0.0;
|
||||||
|
odom.pose.pose.orientation = odom_quat;
|
||||||
|
|
||||||
|
//set the velocity
|
||||||
|
|
||||||
|
odom.twist.twist.linear.x = vx;
|
||||||
|
odom.twist.twist.linear.y = 0.0;
|
||||||
|
odom.twist.twist.angular.z = vth;
|
||||||
|
|
||||||
|
//publish the message
|
||||||
|
odom_publisher_.publish(odom);
|
||||||
|
|
||||||
|
last_time_ = current_time_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::SendCmdToRobot(geometry_msgs::Twist *current_twist_)
|
||||||
|
{
|
||||||
|
static unsigned char index = 0;
|
||||||
|
index++;
|
||||||
|
robot_.SendCommand({current_twist_->linear.x, current_twist_->angular.z, index++});
|
||||||
|
#if Send_Speed_Debug
|
||||||
|
ROS_INFO_STREAM("send -> linear: " << cent_speed << "; angular: " << cmd_twist_rotation);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutROSMessenger::run(void)
|
||||||
|
{
|
||||||
|
ros::NodeHandle private_node("~");
|
||||||
|
ros::NodeHandle node;
|
||||||
|
|
||||||
|
private_node.param<std::string>("port_name_", port_name_, std::string("/dev/ttyUSB0"));
|
||||||
|
private_node.param<std::string>("odom_frame_", odom_frame_, std::string("odom"));
|
||||||
|
private_node.param<std::string>("base_frame_", base_frame_, std::string("base_footprint"));
|
||||||
|
private_node.param<int>("baud_rate_", baud_rate_, 115200);
|
||||||
|
private_node.param<int>("ctrl_rate_", ctrl_rate_, 10);
|
||||||
|
|
||||||
|
// connect to scout
|
||||||
|
robot_.ConnectSerialPort(port_name_, baud_rate_);
|
||||||
|
if (!robot_.IsConnectionActive())
|
||||||
|
{
|
||||||
|
std::cerr << "Failed to connect to robot" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Odometry publisher
|
||||||
|
odom_publisher_ = node.advertise<nav_msgs::Odometry>(odom_frame_, 50);
|
||||||
|
boost::thread parse_thread(boost::bind(&ScoutROSMessenger::PublishOdometry, this));
|
||||||
|
|
||||||
|
// Cmd subscriber
|
||||||
|
ros::Subscriber cmd_sub = node.subscribe<geometry_msgs::Twist>("cmd_vel", 5, &ScoutROSMessenger::TwistCmdCallback, this); //不启用平滑包则订阅“cmd_vel”
|
||||||
|
ros::Timer send_speed_timer = node.createTimer(ros::Duration(1.0 / ctrl_rate_), &ScoutROSMessenger::SendSpeedCmdCallback, this);
|
||||||
|
|
||||||
|
ros::spin();
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ros::init(argc, argv, "scout_odom");
|
||||||
|
|
||||||
|
// start ROS messenger
|
||||||
|
ScoutROSMessenger scout_ros;
|
||||||
|
scout_ros.run();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
16
scout_base/src/scout_sdk/CMakeLists.txt
Normal file
16
scout_base/src/scout_sdk/CMakeLists.txt
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(scout_sdk)
|
||||||
|
|
||||||
|
# generate symbols for IDE indexer
|
||||||
|
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||||
|
set(RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/devel)
|
||||||
|
|
||||||
|
## Chosse build type
|
||||||
|
# set(CMAKE_BUILD_TYPE Release)
|
||||||
|
set(CMAKE_BUILD_TYPE Debug)
|
||||||
|
|
||||||
|
## Optionally built modules: ON/OFF
|
||||||
|
set(BUILD_TESTS OFF)
|
||||||
|
|
||||||
|
## Add source directories
|
||||||
|
add_subdirectory(src)
|
||||||
46
scout_base/src/scout_sdk/README.md
Normal file
46
scout_base/src/scout_sdk/README.md
Normal file
@@ -0,0 +1,46 @@
|
|||||||
|
# Introduction
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
* Data from the chassis:
|
||||||
|
* Odometry (position, velocity estimation)
|
||||||
|
* Data to the chassis:
|
||||||
|
* Motion command (linear/angular velocity)
|
||||||
|
|
||||||
|
# Prerequisites
|
||||||
|
|
||||||
|
* Make sure your user account has access to
|
||||||
|
* serial port (to communicate with robot base)
|
||||||
|
* keyboard input (to use keyboard control)
|
||||||
|
|
||||||
|
* Grant access to serial port
|
||||||
|
```
|
||||||
|
# Note: you can use "ls /dev/ttyUSB*" to check the serial port number on your computer
|
||||||
|
$ sudo chmod 666 /dev/ttyUSB0
|
||||||
|
```
|
||||||
|
|
||||||
|
* Add user to "input" group
|
||||||
|
```
|
||||||
|
$ sudo adduser <your-user-name> input
|
||||||
|
```
|
||||||
|
|
||||||
|
# Build SDK
|
||||||
|
|
||||||
|
Install compile tools
|
||||||
|
```
|
||||||
|
$ sudo apt install build-essential cmake
|
||||||
|
```
|
||||||
|
|
||||||
|
Configure and build
|
||||||
|
```
|
||||||
|
$ cd scout_sdk
|
||||||
|
$ mkdir build
|
||||||
|
$ cd build
|
||||||
|
$ cmake ..
|
||||||
|
$ make
|
||||||
|
```
|
||||||
|
|
||||||
|
# Third-Party Components
|
||||||
|
|
||||||
|
* serial - https://github.com/wjwwood/serial: serial read/write
|
||||||
|
* stopwatch - https://github.com/rxdu/stopwatch: for timing control in demo
|
||||||
BIN
scout_base/src/scout_sdk/docs/scout_interface.png
Normal file
BIN
scout_base/src/scout_sdk/docs/scout_interface.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 53 KiB |
5
scout_base/src/scout_sdk/src/CMakeLists.txt
Normal file
5
scout_base/src/scout_sdk/src/CMakeLists.txt
Normal file
@@ -0,0 +1,5 @@
|
|||||||
|
# Add source directories
|
||||||
|
add_subdirectory(demo)
|
||||||
|
add_subdirectory(scout_cpp)
|
||||||
|
add_subdirectory(scout_io)
|
||||||
|
add_subdirectory(third_party)
|
||||||
6
scout_base/src/scout_sdk/src/demo/CMakeLists.txt
Normal file
6
scout_base/src/scout_sdk/src/demo/CMakeLists.txt
Normal file
@@ -0,0 +1,6 @@
|
|||||||
|
# Dependency libraries
|
||||||
|
#find_package(LIBRARY_NAME REQUIRED)
|
||||||
|
|
||||||
|
# tests
|
||||||
|
add_executable(demo_scout_cpp demo_scout_cpp.cpp)
|
||||||
|
target_link_libraries(demo_scout_cpp scoutcpp stopwatch)
|
||||||
149
scout_base/src/scout_sdk/src/demo/demo_scout_cpp.cpp
Normal file
149
scout_base/src/scout_sdk/src/demo/demo_scout_cpp.cpp
Normal file
@@ -0,0 +1,149 @@
|
|||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <functional>
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
|
#include "stopwatch/stopwatch.h"
|
||||||
|
|
||||||
|
#include "scout/scout_robot.h"
|
||||||
|
|
||||||
|
using namespace scout;
|
||||||
|
|
||||||
|
class ScoutMessenger
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ScoutMessenger(ScoutRobot &robot, int32_t ctrl_freq = 10, int32_t odom_query_freq = 200)
|
||||||
|
: robot_(robot), ctrl_freq_(ctrl_freq), odom_query_freq_(odom_query_freq){};
|
||||||
|
~ScoutMessenger() = default;
|
||||||
|
|
||||||
|
using Clock = std::chrono::high_resolution_clock;
|
||||||
|
using time_point = typename Clock::time_point;
|
||||||
|
|
||||||
|
void PublishOdometry()
|
||||||
|
{
|
||||||
|
RobotState data;
|
||||||
|
stopwatch::StopWatch swatch;
|
||||||
|
|
||||||
|
bool init_run = true;
|
||||||
|
|
||||||
|
/* Odometry Publish Loop */
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
swatch.tic();
|
||||||
|
|
||||||
|
if (robot_.QueryRobotState(&data))
|
||||||
|
{
|
||||||
|
short linear = data.linear;
|
||||||
|
short angular = data.angular;
|
||||||
|
|
||||||
|
current_time_ = Clock::now();
|
||||||
|
double dt = std::chrono::duration_cast<std::chrono::milliseconds>(current_time_ - last_time_).count() / 1000.0;
|
||||||
|
|
||||||
|
if (init_run)
|
||||||
|
{
|
||||||
|
last_time_ = current_time_;
|
||||||
|
init_run = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Velocity estimation
|
||||||
|
double Angular = angular;
|
||||||
|
double Linear = linear;
|
||||||
|
Angular /= 10000;
|
||||||
|
Linear /= 10000;
|
||||||
|
|
||||||
|
vth = Angular; // Angular velocity, when angle is small, approximately = (SPEED_RIGHT - SPEED_LEFT)/ WHEEL_DISTANCE
|
||||||
|
vx = Linear; // Linear velocity (along x axis) = (SPEED_RIGHT - SPEED_LEFT) / 2
|
||||||
|
vy = 0.0; // No lateral motion
|
||||||
|
|
||||||
|
// Pose estimation (by integration)
|
||||||
|
double delta_x = (vx * std::cos(th) - vy * std::sin(th)) * dt;
|
||||||
|
double delta_y = (vx * std::sin(th) + vy * std::cos(th)) * dt;
|
||||||
|
double delta_th = vth * dt;
|
||||||
|
x += delta_x;
|
||||||
|
y += delta_y;
|
||||||
|
th += delta_th;
|
||||||
|
|
||||||
|
// Publish/print result
|
||||||
|
std::cout << "pose: (x,y) " << x << " , " << y << " ; yaw: " << th << std::endl;
|
||||||
|
std::cout << "velocity: linear " << vx << " , angular " << vth << std::endl;
|
||||||
|
|
||||||
|
last_time_ = current_time_;
|
||||||
|
}
|
||||||
|
|
||||||
|
swatch.sleep_until_ms(1000.0 / odom_query_freq_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void UpdateCommandCallback()
|
||||||
|
{
|
||||||
|
// Update linear_x, angular_z via your IPC method
|
||||||
|
// Note: be careful about the sync (using mutex)
|
||||||
|
std::lock_guard<std::mutex> lock(cmd_mutex_);
|
||||||
|
cmd_linear_x_ = 0;
|
||||||
|
cmd_angular_z_ = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SendMotionCommand()
|
||||||
|
{
|
||||||
|
stopwatch::StopWatch swatch;
|
||||||
|
static unsigned char index = 0;
|
||||||
|
|
||||||
|
/* Command Updating Loop */
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
swatch.tic();
|
||||||
|
|
||||||
|
cmd_mutex_.lock();
|
||||||
|
robot_.SendCommand({cmd_linear_x_, cmd_angular_z_, index++});
|
||||||
|
cmd_mutex_.unlock();
|
||||||
|
|
||||||
|
swatch.sleep_until_ms(1000.0 / ctrl_freq_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
ScoutRobot &robot_;
|
||||||
|
int32_t ctrl_freq_;
|
||||||
|
int32_t odom_query_freq_;
|
||||||
|
|
||||||
|
std::mutex cmd_mutex_;
|
||||||
|
double cmd_linear_x_ = 0;
|
||||||
|
double cmd_angular_z_ = 0;
|
||||||
|
|
||||||
|
double x = 0;
|
||||||
|
double y = 0;
|
||||||
|
double th = 0;
|
||||||
|
double vx = 0;
|
||||||
|
double vy = 0;
|
||||||
|
double vth = 0;
|
||||||
|
|
||||||
|
time_point current_time_;
|
||||||
|
time_point last_time_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
/* Connect to a scout robot */
|
||||||
|
ScoutRobot scout;
|
||||||
|
scout.ConnectSerialPort("/dev/ttyUSB0", 115200);
|
||||||
|
if (!scout.IsConnectionActive())
|
||||||
|
{
|
||||||
|
std::cerr << "Failed to connect to robot" << std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Instantiate the messenger and start data distribution */
|
||||||
|
ScoutMessenger messenger(scout);
|
||||||
|
std::thread odom_thread(std::bind(&ScoutMessenger::PublishOdometry, &messenger));
|
||||||
|
std::thread cmd_thread(std::bind(&ScoutMessenger::SendMotionCommand, &messenger));
|
||||||
|
odom_thread.join();
|
||||||
|
cmd_thread.join();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
39
scout_base/src/scout_sdk/src/scout_cpp/CMakeLists.txt
Normal file
39
scout_base/src/scout_sdk/src/scout_cpp/CMakeLists.txt
Normal file
@@ -0,0 +1,39 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(scout_cpp)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
|
## Set compiler to use c++ 11 features
|
||||||
|
include(CheckCXXCompilerFlag)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
|
||||||
|
if(COMPILER_SUPPORTS_CXX14)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX11)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX0X)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
|
||||||
|
else()
|
||||||
|
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++14 or C++11 support. Please use a different C++ compiler.")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
## Add libraries
|
||||||
|
set(SCOUT_CPP_SRC
|
||||||
|
src/scout_robot.cpp
|
||||||
|
)
|
||||||
|
add_library(scoutcpp STATIC ${SCOUT_CPP_SRC})
|
||||||
|
target_link_libraries(scoutcpp scoutio)
|
||||||
|
target_include_directories(scoutcpp PUBLIC
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<BUILD_INTERFACE:${Boost_INCLUDE_DIRS}>
|
||||||
|
$<INSTALL_INTERFACE:include>
|
||||||
|
PRIVATE src)
|
||||||
|
|
||||||
|
## Add executables
|
||||||
|
if(BUILD_TESTS)
|
||||||
|
add_subdirectory(tests)
|
||||||
|
endif()
|
||||||
@@ -0,0 +1,43 @@
|
|||||||
|
#ifndef SCOUT_ROBOT_H
|
||||||
|
#define SCOUT_ROBOT_H
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <cstdint>
|
||||||
|
|
||||||
|
namespace scout
|
||||||
|
{
|
||||||
|
struct RobotState
|
||||||
|
{
|
||||||
|
RobotState() : linear(0), angular(0) {}
|
||||||
|
RobotState(short _linear, short _angular) : linear(_linear), angular(_angular) {}
|
||||||
|
|
||||||
|
short linear;
|
||||||
|
short angular;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct RobotCmd
|
||||||
|
{
|
||||||
|
RobotCmd() : linear(0), angular(0) {}
|
||||||
|
RobotCmd(double _linear, double _angular, uint32_t cnt)
|
||||||
|
: linear(_linear), angular(_angular), count(0) {}
|
||||||
|
|
||||||
|
double linear;
|
||||||
|
double angular;
|
||||||
|
uint32_t count;
|
||||||
|
};
|
||||||
|
|
||||||
|
class ScoutRobot
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
void ConnectSerialPort(const std::string &port_name = "/dev/ttyUSB0", int32_t baud_rate = 115200);
|
||||||
|
bool IsConnectionActive() const { return serial_connected_; }
|
||||||
|
|
||||||
|
void SendCommand(const RobotCmd& cmd);
|
||||||
|
bool QueryRobotState(RobotState *data);
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool serial_connected_ = false;
|
||||||
|
};
|
||||||
|
} // namespace scout
|
||||||
|
|
||||||
|
#endif /* SCOUT_ROBOT_H */
|
||||||
54
scout_base/src/scout_sdk/src/scout_cpp/src/scout_robot.cpp
Normal file
54
scout_base/src/scout_sdk/src/scout_cpp/src/scout_robot.cpp
Normal file
@@ -0,0 +1,54 @@
|
|||||||
|
#include "scout/scout_robot.h"
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "scout_io/serialport.h"
|
||||||
|
#include "scout_io/transport.h"
|
||||||
|
|
||||||
|
namespace scout
|
||||||
|
{
|
||||||
|
void ScoutRobot::ConnectSerialPort(const std::string &port_name, int32_t baud_rate)
|
||||||
|
{
|
||||||
|
serial_connected_ = (scout_serial::Open_Serial(port_name, baud_rate) > 0) ? true : false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ScoutRobot::QueryRobotState(RobotState *data)
|
||||||
|
{
|
||||||
|
scout_transport::Cmd_t cmd;
|
||||||
|
scout_transport::Read_DataOfChassis_Loop();
|
||||||
|
cmd = scout_transport::Get_dataOfTransport();
|
||||||
|
|
||||||
|
if (cmd.IsUpdata == true)
|
||||||
|
{
|
||||||
|
cmd.IsUpdata = false;
|
||||||
|
data->linear = cmd.Linear;
|
||||||
|
data->angular = cmd.Angular;
|
||||||
|
scout_transport::Set_dataOfTransport(&cmd);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScoutRobot::SendCommand(const RobotCmd& cmd)
|
||||||
|
{
|
||||||
|
double cent_speed = cmd.linear;
|
||||||
|
double cmd_twist_rotation = cmd.angular;
|
||||||
|
|
||||||
|
cent_speed = cent_speed * 10000;
|
||||||
|
cmd_twist_rotation = cmd_twist_rotation * 10000;
|
||||||
|
if (cent_speed > 20000)
|
||||||
|
cent_speed = 20000;
|
||||||
|
if (cent_speed < -20000)
|
||||||
|
cent_speed = -20000;
|
||||||
|
if (cmd_twist_rotation > 20000)
|
||||||
|
cmd_twist_rotation = 20000;
|
||||||
|
if (cmd_twist_rotation < -20000)
|
||||||
|
cmd_twist_rotation = -20000;
|
||||||
|
|
||||||
|
scout_transport::Send_Speed(static_cast<short>(cmd_twist_rotation), static_cast<short>(cent_speed), cmd.count);
|
||||||
|
std::cout << "send -> linear: " << cent_speed << "; angular: " << cmd_twist_rotation << std::endl;
|
||||||
|
}
|
||||||
|
} // namespace scout
|
||||||
@@ -0,0 +1,6 @@
|
|||||||
|
# Dependency libraries
|
||||||
|
#find_package(LIBRARY_NAME REQUIRED)
|
||||||
|
|
||||||
|
# tests
|
||||||
|
add_executable(test_scout_cpp test_scout_cpp.cpp)
|
||||||
|
target_link_libraries(test_scout_cpp scoutcpp stopwatch)
|
||||||
152
scout_base/src/scout_sdk/src/scout_cpp/tests/test_scout_cpp.cpp
Normal file
152
scout_base/src/scout_sdk/src/scout_cpp/tests/test_scout_cpp.cpp
Normal file
@@ -0,0 +1,152 @@
|
|||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <functional>
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
|
#include "stopwatch/stopwatch.h"
|
||||||
|
|
||||||
|
#include "scout/scout_robot.h"
|
||||||
|
|
||||||
|
#define TEST_WITHOUT_SERIAL_HARDWARE
|
||||||
|
|
||||||
|
using namespace scout;
|
||||||
|
|
||||||
|
class ScoutMessenger
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
ScoutMessenger(ScoutRobot &robot, int32_t ctrl_freq = 10, int32_t odom_query_freq = 200)
|
||||||
|
: robot_(robot), ctrl_freq_(ctrl_freq), odom_query_freq_(odom_query_freq){};
|
||||||
|
~ScoutMessenger() = default;
|
||||||
|
|
||||||
|
using Clock = std::chrono::high_resolution_clock;
|
||||||
|
using time_point = typename Clock::time_point;
|
||||||
|
|
||||||
|
void PublishOdometry()
|
||||||
|
{
|
||||||
|
RobotState data;
|
||||||
|
stopwatch::StopWatch swatch;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
swatch.tic();
|
||||||
|
|
||||||
|
// std::cout << "odometry loop" << std::endl;
|
||||||
|
|
||||||
|
if (robot_.QueryRobotState(&data))
|
||||||
|
{
|
||||||
|
short linear = data.linear;
|
||||||
|
short angular = data.angular;
|
||||||
|
|
||||||
|
current_time_ = Clock::now();
|
||||||
|
double dt = std::chrono::duration_cast<std::chrono::seconds>(current_time_ - last_time_).count();
|
||||||
|
static int start_flag = 0;
|
||||||
|
|
||||||
|
//初始化
|
||||||
|
if (start_flag)
|
||||||
|
{
|
||||||
|
last_time_ = current_time_;
|
||||||
|
start_flag = 1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
double Angular = angular;
|
||||||
|
double Linear = linear;
|
||||||
|
Angular /= 10000;
|
||||||
|
Linear /= 10000;
|
||||||
|
|
||||||
|
vth = Angular; //旋转角速度,在角度很小的情况下。约等于(SPEED右 - SPEED左)/ 轮子间距
|
||||||
|
vx = Linear; //直线X轴的速度 = (SPEED右 - SPEED左) / 2
|
||||||
|
vy = 0.0; //2轮差速车,不能左右横移
|
||||||
|
|
||||||
|
double delta_x = (vx * std::cos(th) - vy * std::sin(th)) * dt;
|
||||||
|
double delta_y = (vx * std::sin(th) + vy * std::cos(th)) * dt;
|
||||||
|
double delta_th = vth * dt;
|
||||||
|
|
||||||
|
x += delta_x;
|
||||||
|
y += delta_y;
|
||||||
|
th += delta_th;
|
||||||
|
|
||||||
|
std::cout << "pose: (x,y) " << x << " , " << y << " ; yaw: " << th << std::endl;
|
||||||
|
std::cout << "velocity: linear " << vx << " , angular " << vth << std::endl;
|
||||||
|
|
||||||
|
last_time_ = current_time_;
|
||||||
|
}
|
||||||
|
|
||||||
|
swatch.sleep_until_ms(1000.0 / odom_query_freq_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void UpdateCommandCallback()
|
||||||
|
{
|
||||||
|
// Update linear_x, angular_z via your IPC method
|
||||||
|
// Note: be careful about the sync (using mutex)
|
||||||
|
std::lock_guard<std::mutex> lock(cmd_mutex_);
|
||||||
|
cmd_linear_x_ = 0;
|
||||||
|
cmd_angular_z_ = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void SendMotionCommand()
|
||||||
|
{
|
||||||
|
stopwatch::StopWatch swatch;
|
||||||
|
static unsigned char index = 0;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
swatch.tic();
|
||||||
|
|
||||||
|
// std::cout << "cmd loop" << std::endl;
|
||||||
|
cmd_mutex_.lock();
|
||||||
|
#ifndef TEST_WITHOUT_SERIAL_HARDWARE
|
||||||
|
robot_.SendCommand(cmd_linear_x_, cmd_angular_z_, index++);
|
||||||
|
#endif
|
||||||
|
cmd_mutex_.unlock();
|
||||||
|
swatch.sleep_until_ms(1000.0 / ctrl_freq_);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
ScoutRobot &robot_;
|
||||||
|
int32_t ctrl_freq_;
|
||||||
|
int32_t odom_query_freq_;
|
||||||
|
|
||||||
|
std::mutex cmd_mutex_;
|
||||||
|
double cmd_linear_x_ = 0;
|
||||||
|
double cmd_angular_z_ = 0;
|
||||||
|
|
||||||
|
double x = 0;
|
||||||
|
double y = 0;
|
||||||
|
double th = 0;
|
||||||
|
double vx = 0;
|
||||||
|
double vy = 0;
|
||||||
|
double vth = 0;
|
||||||
|
|
||||||
|
time_point current_time_;
|
||||||
|
time_point last_time_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char **argv)
|
||||||
|
{
|
||||||
|
ScoutRobot scout;
|
||||||
|
|
||||||
|
#ifndef TEST_WITHOUT_SERIAL_HARDWARE
|
||||||
|
scout.ConnectSerialPort("/dev/ttyUSB0", 115200);
|
||||||
|
|
||||||
|
if (!scout.IsConnectionActive())
|
||||||
|
{
|
||||||
|
std::cerr << "Failed to connect to robot" << std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
ScoutMessenger messenger(scout);
|
||||||
|
std::thread odom_thread(std::bind(&ScoutMessenger::PublishOdometry, &messenger));
|
||||||
|
std::thread cmd_thread(std::bind(&ScoutMessenger::SendMotionCommand, &messenger));
|
||||||
|
|
||||||
|
odom_thread.join();
|
||||||
|
cmd_thread.join();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
34
scout_base/src/scout_sdk/src/scout_io/CMakeLists.txt
Normal file
34
scout_base/src/scout_sdk/src/scout_io/CMakeLists.txt
Normal file
@@ -0,0 +1,34 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(scout_io)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
|
## Set compiler to use c++ 11 features
|
||||||
|
include(CheckCXXCompilerFlag)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
|
||||||
|
if(COMPILER_SUPPORTS_CXX14)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX11)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX0X)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
|
||||||
|
else()
|
||||||
|
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++14 or C++11 support. Please use a different C++ compiler.")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
## Add libraries
|
||||||
|
set(SCOUT_IO_SRC
|
||||||
|
src/serialport.cpp
|
||||||
|
src/transport.cpp
|
||||||
|
)
|
||||||
|
add_library(scoutio STATIC ${SCOUT_IO_SRC})
|
||||||
|
target_link_libraries(scoutio serial)
|
||||||
|
target_include_directories(scoutio PUBLIC
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>
|
||||||
|
PRIVATE src)
|
||||||
@@ -0,0 +1,14 @@
|
|||||||
|
#ifndef SERIALPORT_H
|
||||||
|
#define SERIALPORT_H
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
namespace scout_serial
|
||||||
|
{
|
||||||
|
int Open_Serial(std::string port_name, int baud_rate);
|
||||||
|
unsigned int Write(unsigned char *data, unsigned short len);
|
||||||
|
unsigned int Read(unsigned char *data, unsigned short len);
|
||||||
|
unsigned int GetDataCount(void);
|
||||||
|
} // namespace scout_serial
|
||||||
|
|
||||||
|
#endif /* SERIALPORT_H */
|
||||||
@@ -0,0 +1,43 @@
|
|||||||
|
#ifndef TRANSPORT_H
|
||||||
|
#define TRANSPORT_H
|
||||||
|
|
||||||
|
namespace scout_transport
|
||||||
|
{
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
unsigned short Header;
|
||||||
|
unsigned char Len;
|
||||||
|
unsigned char Typedef;
|
||||||
|
unsigned char Count;
|
||||||
|
unsigned char Time_Out;
|
||||||
|
short Linear;
|
||||||
|
short Angular;
|
||||||
|
unsigned short CheckSum;
|
||||||
|
} Frame_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
unsigned short Linear;
|
||||||
|
unsigned short Angular;
|
||||||
|
bool IsUpdata;
|
||||||
|
} Cmd_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
eHead = 0,
|
||||||
|
eLen = 1,
|
||||||
|
eTypedef = 3,
|
||||||
|
eChecksum = 2
|
||||||
|
} state_t;
|
||||||
|
|
||||||
|
Cmd_t Get_dataOfTransport();
|
||||||
|
void Set_dataOfTransport(Cmd_t *CMD);
|
||||||
|
void Read_DataOfChassis_Loop(void);
|
||||||
|
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count);
|
||||||
|
void Send_Speed(short Angular, short Linear, unsigned char Count);
|
||||||
|
unsigned short Checksum(unsigned char *data, unsigned short len);
|
||||||
|
void Find_NextHead();
|
||||||
|
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count);
|
||||||
|
} // namespace scout_transport
|
||||||
|
|
||||||
|
#endif /* TRANSPORT_H */
|
||||||
58
scout_base/src/scout_sdk/src/scout_io/src/serialport.cpp
Normal file
58
scout_base/src/scout_sdk/src/scout_io/src/serialport.cpp
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include <serial/serial.h>
|
||||||
|
|
||||||
|
#include "scout_io/serialport.h"
|
||||||
|
|
||||||
|
namespace
|
||||||
|
{
|
||||||
|
serial::Serial ser;
|
||||||
|
}
|
||||||
|
|
||||||
|
namespace scout_serial
|
||||||
|
{
|
||||||
|
int Open_Serial(std::string port_name, int baud_rate)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
// 设置串口属性,并打开串口 Configure and open serial port
|
||||||
|
ser.setPort(port_name);
|
||||||
|
ser.setBaudrate(baud_rate);
|
||||||
|
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
|
||||||
|
ser.setTimeout(to);
|
||||||
|
ser.open();
|
||||||
|
}
|
||||||
|
catch (serial::IOException &e)
|
||||||
|
{
|
||||||
|
std::cerr << "Unable to open port " << std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ser.isOpen())
|
||||||
|
{
|
||||||
|
std::cerr << "Serial Port initialized" << std::endl;
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned int Write(unsigned char *data, unsigned short len)
|
||||||
|
{
|
||||||
|
unsigned int Len = ser.write(data, len);
|
||||||
|
return Len;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned int Read(unsigned char *data, unsigned short len)
|
||||||
|
{
|
||||||
|
unsigned int Len = ser.read(data, len);
|
||||||
|
return Len;
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned int GetDataCount(void)
|
||||||
|
{
|
||||||
|
return ser.available();
|
||||||
|
}
|
||||||
|
} // namespace scout_serial
|
||||||
193
scout_base/src/scout_sdk/src/scout_io/src/transport.cpp
Normal file
193
scout_base/src/scout_sdk/src/scout_io/src/transport.cpp
Normal file
@@ -0,0 +1,193 @@
|
|||||||
|
#include <iostream>
|
||||||
|
#include <thread>
|
||||||
|
#include <mutex>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
#include "scout_io/serialport.h"
|
||||||
|
#include "scout_io/transport.h"
|
||||||
|
|
||||||
|
#define serial_debug 1
|
||||||
|
#define receive_speed_callback_debug 0
|
||||||
|
#define receive_odom_debug 1
|
||||||
|
|
||||||
|
namespace
|
||||||
|
{
|
||||||
|
#define ChassisToRos_Odom 0x56
|
||||||
|
#define RosToChassis_Cmd 0x12
|
||||||
|
|
||||||
|
bool Is_send_speed_callback;
|
||||||
|
|
||||||
|
scout_transport::Frame_t Get_Odom_Frame;
|
||||||
|
scout_transport::Cmd_t cmd;
|
||||||
|
|
||||||
|
std::mutex ack_write;
|
||||||
|
std::mutex cmd_write;
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
namespace scout_transport
|
||||||
|
{
|
||||||
|
unsigned short Checksum(unsigned char *data, unsigned short len)
|
||||||
|
{
|
||||||
|
unsigned short i = 0;
|
||||||
|
unsigned short sum = 0;
|
||||||
|
for (i = 0; i < len; i++)
|
||||||
|
{
|
||||||
|
sum += data[i];
|
||||||
|
}
|
||||||
|
return sum;
|
||||||
|
}
|
||||||
|
|
||||||
|
void Send_Speed(short Angular, short Linear, unsigned char Count)
|
||||||
|
{
|
||||||
|
Frame_t Cmd_Frame;
|
||||||
|
memset(&Cmd_Frame, 0, sizeof(Cmd_Frame));
|
||||||
|
Cmd_Frame.Header = 0x55aa;
|
||||||
|
Cmd_Frame.Len = sizeof(Cmd_Frame) - 2;
|
||||||
|
Cmd_Frame.Typedef = RosToChassis_Cmd;
|
||||||
|
Cmd_Frame.Count = Count;
|
||||||
|
Cmd_Frame.Angular = Angular;
|
||||||
|
Cmd_Frame.Linear = Linear;
|
||||||
|
Cmd_Frame.CheckSum = Checksum((unsigned char *)&Cmd_Frame, Cmd_Frame.Len);
|
||||||
|
scout_serial::Write((unsigned char *)&Cmd_Frame, sizeof(Cmd_Frame));
|
||||||
|
}
|
||||||
|
|
||||||
|
void Read_DataOfChassis(void)
|
||||||
|
{
|
||||||
|
static int state = 0;
|
||||||
|
static int len_index = 0;
|
||||||
|
static unsigned char len = 0;
|
||||||
|
static unsigned char buff[30] = {0};
|
||||||
|
|
||||||
|
switch (state)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
{
|
||||||
|
scout_serial::Read(&buff[0], 1);
|
||||||
|
if (buff[0] == 0xaa)
|
||||||
|
{
|
||||||
|
len_index = 0;
|
||||||
|
state = 1;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
printf("Head error 1\r\n");
|
||||||
|
state = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 1:
|
||||||
|
{
|
||||||
|
scout_serial::Read(&buff[1], 1);
|
||||||
|
if (buff[1] == 0x55)
|
||||||
|
{
|
||||||
|
len_index = 0;
|
||||||
|
state = 2;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
printf("Head error 2\r\n");
|
||||||
|
state = 0;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:
|
||||||
|
{
|
||||||
|
scout_serial::Read(&buff[2], 1);
|
||||||
|
len = buff[2];
|
||||||
|
if (len == 10)
|
||||||
|
{
|
||||||
|
state = 3;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
state = 0;
|
||||||
|
printf("Len error 1 : %d \r\n", buff[2]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 3:
|
||||||
|
{
|
||||||
|
scout_serial::Read(&buff[3], len - 1);
|
||||||
|
unsigned short CheckSum = buff[len] | buff[len + 1] << 8;
|
||||||
|
if (CheckSum == Checksum(&buff[0], len))
|
||||||
|
{
|
||||||
|
state = 4;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
state = 0;
|
||||||
|
printf("Check sum error \r\n");
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 4:
|
||||||
|
{
|
||||||
|
unsigned char Typedef = buff[3];
|
||||||
|
if (Typedef == ChassisToRos_Odom)
|
||||||
|
{
|
||||||
|
memcpy(&Get_Odom_Frame, &buff[0], sizeof(Get_Odom_Frame));
|
||||||
|
|
||||||
|
cmd.IsUpdata = true;
|
||||||
|
cmd.Angular = Get_Odom_Frame.Angular;
|
||||||
|
cmd.Linear = Get_Odom_Frame.Linear;
|
||||||
|
|
||||||
|
static int Successful_Connection = 0;
|
||||||
|
|
||||||
|
if (Successful_Connection == 0)
|
||||||
|
{
|
||||||
|
Successful_Connection = 1;
|
||||||
|
printf("The connection was successful and the vehicle was ready!");
|
||||||
|
}
|
||||||
|
|
||||||
|
#if receive_odom_debug
|
||||||
|
printf("Angular = %d Linear = %d count = %d Time_Out = %d \r\n",
|
||||||
|
Get_Odom_Frame.Angular,
|
||||||
|
Get_Odom_Frame.Linear,
|
||||||
|
Get_Odom_Frame.Count,
|
||||||
|
Get_Odom_Frame.Time_Out);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
state = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
state = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
Cmd_t Get_dataOfTransport() { return cmd; }
|
||||||
|
|
||||||
|
void Set_dataOfTransport(Cmd_t *CMD) { cmd = *CMD; }
|
||||||
|
|
||||||
|
void Read_DataOfChassis_Loop(void)
|
||||||
|
{
|
||||||
|
unsigned int len = scout_serial::GetDataCount();
|
||||||
|
if (len >= sizeof(Frame_t))
|
||||||
|
{
|
||||||
|
Read_DataOfChassis();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void Send_SpeedToChassis(short Angular, short Linear, unsigned char Count)
|
||||||
|
{
|
||||||
|
Is_send_speed_callback = false;
|
||||||
|
static int time = 0;
|
||||||
|
time = 0;
|
||||||
|
do
|
||||||
|
{
|
||||||
|
Send_Speed(Angular, Linear, Count);
|
||||||
|
// boost::this_thread::sleep(boost::posix_time::milliseconds(60));
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(60));
|
||||||
|
time++;
|
||||||
|
if (time > 20)
|
||||||
|
{
|
||||||
|
// ROS_INFO_STREAM("lost scout! Please check whether the power supply or the serial line of the vehicle is loose.\r\n");
|
||||||
|
std::cout << "Lost Scout! Please check whether the power supply or the serial cable of the vehicle is loose." << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} while (Is_send_speed_callback == false);
|
||||||
|
}
|
||||||
|
} // namespace scout_transport
|
||||||
11
scout_base/src/scout_sdk/src/third_party/CMakeLists.txt
vendored
Normal file
11
scout_base/src/scout_sdk/src/third_party/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,11 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(scout_thirdparty)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
#set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
|
## Add sub source directories
|
||||||
|
add_subdirectory(serial)
|
||||||
|
add_subdirectory(stopwatch)
|
||||||
85
scout_base/src/scout_sdk/src/third_party/serial/CHANGELOG.rst
vendored
Normal file
85
scout_base/src/scout_sdk/src/third_party/serial/CHANGELOG.rst
vendored
Normal file
@@ -0,0 +1,85 @@
|
|||||||
|
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||||
|
Changelog for package serial
|
||||||
|
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||||
|
|
||||||
|
1.2.1 (2015-04-21)
|
||||||
|
------------------
|
||||||
|
* Removed the use of a C++11 feature for compatibility with older browsers.
|
||||||
|
* Fixed an issue with cross compiling with mingw on Windows.
|
||||||
|
* Restructured Visual Studio project layout.
|
||||||
|
* Added include of ``#include <AvailabilityMacros.h>`` on OS X (listing of ports).
|
||||||
|
* Fixed MXE for the listing of ports on Windows.
|
||||||
|
* Now closes file device if ``reconfigureDevice`` fails (Windows).
|
||||||
|
* Added the MARK/SPACE parity bit option, also made it optional.
|
||||||
|
Adding the enumeration values for MARK and SPACE was the only code change to an API header.
|
||||||
|
It should not affect ABI or API.
|
||||||
|
* Added support for 576000 baud on Linux.
|
||||||
|
* Now releases iterator properly in listing of ports code for OS X.
|
||||||
|
* Fixed the ability to open COM ports over COM10 on Windows.
|
||||||
|
* Fixed up some documentation about exceptions in ``serial.h``.
|
||||||
|
|
||||||
|
1.2.0 (2014-07-02)
|
||||||
|
------------------
|
||||||
|
* Removed vestigial ``read_cache_`` private member variable from Serial::Serial
|
||||||
|
* Fixed usage of scoped locks
|
||||||
|
Previously they were getting destroyed immediately because they were not stored in a temporary scope variable
|
||||||
|
* Added check of return value from close in Serial::SerialImpl::close () in unix.cc and win.cc
|
||||||
|
* Added ability to enumerate ports on linux and windows.
|
||||||
|
Updated serial_example.cc to show example of port enumeration.
|
||||||
|
* Fixed compile on VS2013
|
||||||
|
* Added functions ``waitReadable`` and ``waitByteTimes`` with implemenations for Unix to support high performance reading
|
||||||
|
* Contributors: Christopher Baker, Craig Lilley, Konstantina Kastanara, Mike Purvis, William Woodall
|
||||||
|
|
||||||
|
1.1.7 (2014-02-20)
|
||||||
|
------------------
|
||||||
|
* Improved support for mingw (mxe.cc)
|
||||||
|
* Fix compilation warning
|
||||||
|
See issue `#53 <https://github.com/wjwwood/serial/issues/53>`_
|
||||||
|
* Improved timer handling in unix implementation
|
||||||
|
* fix broken ifdef _WIN32
|
||||||
|
* Fix broken ioctl calls, add exception handling.
|
||||||
|
* Code guards for platform-specific implementations. (when not using cmake / catkin)
|
||||||
|
* Contributors: Christopher Baker, Mike Purvis, Nicolas Bigaouette, William Woodall, dawid
|
||||||
|
|
||||||
|
1.1.6 (2013-10-17)
|
||||||
|
------------------
|
||||||
|
* Move stopbits_one_point_five to the end of the enum, so that it doesn't alias with stopbits_two.
|
||||||
|
|
||||||
|
1.1.5 (2013-09-23)
|
||||||
|
------------------
|
||||||
|
* Fix license labeling, I put BSD, but the license has always been MIT...
|
||||||
|
* Added Microsoft Visual Studio 2010 project to make compiling on Windows easier.
|
||||||
|
* Implemented Serial::available() for Windows
|
||||||
|
* Update how custom baudrates are handled on OS X
|
||||||
|
This is taken from the example serial program on Apple's developer website, see:
|
||||||
|
http://free-pascal-general.1045716.n5.nabble.com/Non-standard-baud-rates-in-OS-X-IOSSIOSPEED-IOCTL-td4699923.html
|
||||||
|
* Timout settings are now applied by reconfigurePort
|
||||||
|
* Pass LPCWSTR to CreateFile in Windows impl
|
||||||
|
* Use wstring for ``port_`` type in Windows impl
|
||||||
|
|
||||||
|
1.1.4 (2013-06-12 00:13:18 -0600)
|
||||||
|
---------------------------------
|
||||||
|
* Timing calculation fix for read and write.
|
||||||
|
Fixes `#27 <https://github.com/wjwwood/serial/issues/27>`_
|
||||||
|
* Update list of exceptions thrown from constructor.
|
||||||
|
* fix, by Thomas Hoppe <thomas.hoppe@cesys.com>
|
||||||
|
For SerialException's:
|
||||||
|
* The name was misspelled...
|
||||||
|
* Use std::string's for error messages to prevent corruption of messages on some platforms
|
||||||
|
* alloca.h does not exist on OpenBSD either.
|
||||||
|
|
||||||
|
1.1.3 (2013-01-09 10:54:34 -0800)
|
||||||
|
---------------------------------
|
||||||
|
* Install headers
|
||||||
|
|
||||||
|
1.1.2 (2012-12-14 14:08:55 -0800)
|
||||||
|
---------------------------------
|
||||||
|
* Fix buildtool depends
|
||||||
|
|
||||||
|
1.1.1 (2012-12-03)
|
||||||
|
------------------
|
||||||
|
* Removed rt linking on OS X. Fixes `#24 <https://github.com/wjwwood/serial/issues/24>`_.
|
||||||
|
|
||||||
|
1.1.0 (2012-10-24)
|
||||||
|
------------------
|
||||||
|
* Previous history is unstructured and therefore has been truncated. See the commit messages for more info.
|
||||||
86
scout_base/src/scout_sdk/src/third_party/serial/CMakeLists.txt
vendored
Normal file
86
scout_base/src/scout_sdk/src/third_party/serial/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,86 @@
|
|||||||
|
cmake_minimum_required(VERSION 2.8.3)
|
||||||
|
project(serial)
|
||||||
|
|
||||||
|
## Put all binary files into /bin and libraries into /lib
|
||||||
|
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||||
|
set(LIBRARY_OUTPUT_PATH ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
set(ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
|
||||||
|
|
||||||
|
## Set compiler to use c++ 11 features
|
||||||
|
include(CheckCXXCompilerFlag)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
|
||||||
|
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
|
||||||
|
if(COMPILER_SUPPORTS_CXX14)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX11)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
|
||||||
|
elseif(COMPILER_SUPPORTS_CXX0X)
|
||||||
|
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
|
||||||
|
else()
|
||||||
|
message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++14 or C++11 support. Please use a different C++ compiler.")
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(APPLE)
|
||||||
|
find_library(IOKIT_LIBRARY IOKit)
|
||||||
|
find_library(FOUNDATION_LIBRARY Foundation)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
## Include headers
|
||||||
|
include_directories(include)
|
||||||
|
|
||||||
|
# if(UNIX AND NOT APPLE)
|
||||||
|
# # If Linux, add rt and pthread
|
||||||
|
# set(rt_LIBRARIES rt)
|
||||||
|
# set(pthread_LIBRARIES pthread)
|
||||||
|
# catkin_package(
|
||||||
|
# LIBRARIES ${PROJECT_NAME}
|
||||||
|
# INCLUDE_DIRS include
|
||||||
|
# DEPENDS rt pthread
|
||||||
|
# )
|
||||||
|
# else()
|
||||||
|
# # Otherwise normal call
|
||||||
|
# catkin_package(
|
||||||
|
# LIBRARIES ${PROJECT_NAME}
|
||||||
|
# INCLUDE_DIRS include
|
||||||
|
# )
|
||||||
|
# endif()
|
||||||
|
|
||||||
|
## Sources
|
||||||
|
set(serial_SRCS
|
||||||
|
src/serial.cc
|
||||||
|
include/serial/serial.h
|
||||||
|
include/serial/v8stdint.h
|
||||||
|
)
|
||||||
|
if(APPLE)
|
||||||
|
# If OSX
|
||||||
|
list(APPEND serial_SRCS src/impl/unix.cc)
|
||||||
|
list(APPEND serial_SRCS src/impl/list_ports/list_ports_osx.cc)
|
||||||
|
elseif(UNIX)
|
||||||
|
# If unix
|
||||||
|
list(APPEND serial_SRCS src/impl/unix.cc)
|
||||||
|
list(APPEND serial_SRCS src/impl/list_ports/list_ports_linux.cc)
|
||||||
|
else()
|
||||||
|
# If windows
|
||||||
|
list(APPEND serial_SRCS src/impl/win.cc)
|
||||||
|
list(APPEND serial_SRCS src/impl/list_ports/list_ports_win.cc)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
## Add serial library
|
||||||
|
add_library(${PROJECT_NAME} ${serial_SRCS})
|
||||||
|
if(APPLE)
|
||||||
|
target_link_libraries(${PROJECT_NAME} ${FOUNDATION_LIBRARY} ${IOKIT_LIBRARY})
|
||||||
|
elseif(UNIX)
|
||||||
|
target_link_libraries(${PROJECT_NAME} rt pthread)
|
||||||
|
else()
|
||||||
|
target_link_libraries(${PROJECT_NAME} setupapi)
|
||||||
|
endif()
|
||||||
|
target_include_directories(${PROJECT_NAME} PUBLIC
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>
|
||||||
|
PRIVATE src)
|
||||||
|
|
||||||
|
## Uncomment for example
|
||||||
|
# add_executable(serial_example examples/serial_example.cc)
|
||||||
|
# add_dependencies(serial_example ${PROJECT_NAME})
|
||||||
|
# target_link_libraries(serial_example ${PROJECT_NAME})
|
||||||
74
scout_base/src/scout_sdk/src/third_party/serial/README.md
vendored
Normal file
74
scout_base/src/scout_sdk/src/third_party/serial/README.md
vendored
Normal file
@@ -0,0 +1,74 @@
|
|||||||
|
# Serial Communication Library
|
||||||
|
|
||||||
|
[](https://travis-ci.org/wjwwood/serial)*(Linux and OS X)* [](https://ci.appveyor.com/project/wjwwood/serial)*(Windows)*
|
||||||
|
|
||||||
|
This is a cross-platform library for interfacing with rs-232 serial like ports written in C++. It provides a modern C++ interface with a workflow designed to look and feel like PySerial, but with the speed and control provided by C++.
|
||||||
|
|
||||||
|
This library is in use in several robotics related projects and can be built and installed to the OS like most unix libraries with make and then sudo make install, but because it is a catkin project it can also be built along side other catkin projects in a catkin workspace.
|
||||||
|
|
||||||
|
Serial is a class that provides the basic interface common to serial libraries (open, close, read, write, etc..) and requires no extra dependencies. It also provides tight control over timeouts and control over handshaking lines.
|
||||||
|
|
||||||
|
### Documentation
|
||||||
|
|
||||||
|
Website: http://wjwwood.github.com/serial/
|
||||||
|
|
||||||
|
API Documentation: http://wjwwood.github.com/serial/doc/1.1.0/index.html
|
||||||
|
|
||||||
|
### Dependencies
|
||||||
|
|
||||||
|
Required:
|
||||||
|
* [catkin](http://www.ros.org/wiki/catkin) - cmake and Python based buildsystem
|
||||||
|
* [cmake](http://www.cmake.org) - buildsystem
|
||||||
|
* [Python](http://www.python.org) - scripting language
|
||||||
|
* [empy](http://www.alcyone.com/pyos/empy/) - Python templating library
|
||||||
|
* [catkin_pkg](http://pypi.python.org/pypi/catkin_pkg/) - Runtime Python library for catkin
|
||||||
|
|
||||||
|
Optional (for tests):
|
||||||
|
* [Boost](http://www.boost.org/) - Boost C++ librairies
|
||||||
|
|
||||||
|
Optional (for documentation):
|
||||||
|
* [Doxygen](http://www.doxygen.org/) - Documentation generation tool
|
||||||
|
* [graphviz](http://www.graphviz.org/) - Graph visualization software
|
||||||
|
|
||||||
|
### Install
|
||||||
|
|
||||||
|
Get the code:
|
||||||
|
|
||||||
|
git clone https://github.com/wjwwood/serial.git
|
||||||
|
|
||||||
|
Build:
|
||||||
|
|
||||||
|
make
|
||||||
|
|
||||||
|
Build and run the tests:
|
||||||
|
|
||||||
|
make test
|
||||||
|
|
||||||
|
Build the documentation:
|
||||||
|
|
||||||
|
make doc
|
||||||
|
|
||||||
|
Install:
|
||||||
|
|
||||||
|
make install
|
||||||
|
|
||||||
|
### License
|
||||||
|
|
||||||
|
The MIT License
|
||||||
|
|
||||||
|
Copyright (c) 2012 William Woodall, John Harrison
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||||
|
|
||||||
|
### Authors
|
||||||
|
|
||||||
|
William Woodall <wjwwood@gmail.com>
|
||||||
|
John Harrison <ash.gti@gmail.com>
|
||||||
|
|
||||||
|
### Contact
|
||||||
|
|
||||||
|
William Woodall <william@osrfoundation.org>
|
||||||
10
scout_base/src/scout_sdk/src/third_party/serial/changes.txt
vendored
Normal file
10
scout_base/src/scout_sdk/src/third_party/serial/changes.txt
vendored
Normal file
@@ -0,0 +1,10 @@
|
|||||||
|
# 1.1.0 10-24-2012
|
||||||
|
|
||||||
|
* Converted the build system to catkin
|
||||||
|
|
||||||
|
# v1.0.1 8-27-2012
|
||||||
|
|
||||||
|
* Added baudrates: 1000000, 11520000, 2000000, 2500000, 3000000, 3500000, and 4000000
|
||||||
|
* Linking related bug fixes on Linux and OS X
|
||||||
|
* Custom baudrate bug fix. Closes issue #18.
|
||||||
|
|
||||||
2430
scout_base/src/scout_sdk/src/third_party/serial/doc/Doxyfile
vendored
Normal file
2430
scout_base/src/scout_sdk/src/third_party/serial/doc/Doxyfile
vendored
Normal file
File diff suppressed because it is too large
Load Diff
58
scout_base/src/scout_sdk/src/third_party/serial/doc/serial.dox
vendored
Normal file
58
scout_base/src/scout_sdk/src/third_party/serial/doc/serial.dox
vendored
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
/*!
|
||||||
|
\mainpage Serial Library
|
||||||
|
|
||||||
|
\author William Woodall <wjwwood@gmail.com>, John Harrison <ash@greaterthaninfinity.com>
|
||||||
|
|
||||||
|
\section what_is What is serial?
|
||||||
|
Serial is a cross-platform, simple to use library for using serial ports on computers. This library provides a C++, object oriented interface for interacting with RS-232 like devices on Linux and Windows.
|
||||||
|
|
||||||
|
Want to use it with ROS(Robot Operating System)? No problem, it compiles as a unary stack.
|
||||||
|
|
||||||
|
\section getting_started Getting Started
|
||||||
|
|
||||||
|
Ready to jump in?
|
||||||
|
- Checkout our examples: \ref serial_example.cc
|
||||||
|
- Look at the main class documentation: \ref serial::Serial
|
||||||
|
|
||||||
|
\section features Features
|
||||||
|
- Linux, Mac OS X, and Windows Support
|
||||||
|
- Easy to use interface (modeled after PySerial)
|
||||||
|
- Minimal dependencies (cmake)
|
||||||
|
- Complete timeout control \ref serial::Serial::setTimeout
|
||||||
|
- Check and set handshaking lines (CTS, DSR, RI, CD and RTS, DTR)
|
||||||
|
- Block for changes in handshaking lines (Linux and Windows)
|
||||||
|
- Flush I/O separately and block until all writing done
|
||||||
|
|
||||||
|
\section install Installation
|
||||||
|
|
||||||
|
\subsection Dependencies
|
||||||
|
|
||||||
|
- CMake:
|
||||||
|
- CMake is required for building the system and can be located here: http://www.cmake.org/
|
||||||
|
|
||||||
|
\subsection building Compiling
|
||||||
|
|
||||||
|
Once you have gathered the dependencies, you need to checkout the software from github.com:
|
||||||
|
|
||||||
|
<pre>
|
||||||
|
git clone git://github.com/wjwwood/serial.git
|
||||||
|
</pre>
|
||||||
|
|
||||||
|
Once you have checked out the source code from github.com you can enter the directory and build the software.
|
||||||
|
|
||||||
|
<pre>
|
||||||
|
cd serial
|
||||||
|
make
|
||||||
|
make test # (optional) builds the example and tests, and runs the tests.
|
||||||
|
make doc # (optional) builds _this_ documentation.
|
||||||
|
</pre>
|
||||||
|
|
||||||
|
\subsection installing Installing
|
||||||
|
|
||||||
|
To install simply:
|
||||||
|
|
||||||
|
<pre>
|
||||||
|
sudo make install
|
||||||
|
</pre>
|
||||||
|
|
||||||
|
*/
|
||||||
182
scout_base/src/scout_sdk/src/third_party/serial/examples/serial_example.cc
vendored
Normal file
182
scout_base/src/scout_sdk/src/third_party/serial/examples/serial_example.cc
vendored
Normal file
@@ -0,0 +1,182 @@
|
|||||||
|
/***
|
||||||
|
* This example expects the serial port has a loopback on it.
|
||||||
|
*
|
||||||
|
* Alternatively, you could use an Arduino:
|
||||||
|
*
|
||||||
|
* <pre>
|
||||||
|
* void setup() {
|
||||||
|
* Serial.begin(<insert your baudrate here>);
|
||||||
|
* }
|
||||||
|
*
|
||||||
|
* void loop() {
|
||||||
|
* if (Serial.available()) {
|
||||||
|
* Serial.write(Serial.read());
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* </pre>
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <iostream>
|
||||||
|
#include <cstdio>
|
||||||
|
|
||||||
|
// OS Specific sleep
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include <windows.h>
|
||||||
|
#else
|
||||||
|
#include <unistd.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
using std::string;
|
||||||
|
using std::exception;
|
||||||
|
using std::cout;
|
||||||
|
using std::cerr;
|
||||||
|
using std::endl;
|
||||||
|
using std::vector;
|
||||||
|
|
||||||
|
void my_sleep(unsigned long milliseconds) {
|
||||||
|
#ifdef _WIN32
|
||||||
|
Sleep(milliseconds); // 100 ms
|
||||||
|
#else
|
||||||
|
usleep(milliseconds*1000); // 100 ms
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void enumerate_ports()
|
||||||
|
{
|
||||||
|
vector<serial::PortInfo> devices_found = serial::list_ports();
|
||||||
|
|
||||||
|
vector<serial::PortInfo>::iterator iter = devices_found.begin();
|
||||||
|
|
||||||
|
while( iter != devices_found.end() )
|
||||||
|
{
|
||||||
|
serial::PortInfo device = *iter++;
|
||||||
|
|
||||||
|
printf( "(%s, %s, %s)\n", device.port.c_str(), device.description.c_str(),
|
||||||
|
device.hardware_id.c_str() );
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_usage()
|
||||||
|
{
|
||||||
|
cerr << "Usage: test_serial {-e|<serial port address>} ";
|
||||||
|
cerr << "<baudrate> [test string]" << endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
int run(int argc, char **argv)
|
||||||
|
{
|
||||||
|
if(argc < 2) {
|
||||||
|
print_usage();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Argument 1 is the serial port or enumerate flag
|
||||||
|
string port(argv[1]);
|
||||||
|
|
||||||
|
if( port == "-e" ) {
|
||||||
|
enumerate_ports();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
else if( argc < 3 ) {
|
||||||
|
print_usage();
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Argument 2 is the baudrate
|
||||||
|
unsigned long baud = 0;
|
||||||
|
#if defined(WIN32) && !defined(__MINGW32__)
|
||||||
|
sscanf_s(argv[2], "%lu", &baud);
|
||||||
|
#else
|
||||||
|
sscanf(argv[2], "%lu", &baud);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// port, baudrate, timeout in milliseconds
|
||||||
|
serial::Serial my_serial(port, baud, serial::Timeout::simpleTimeout(1000));
|
||||||
|
|
||||||
|
cout << "Is the serial port open?";
|
||||||
|
if(my_serial.isOpen())
|
||||||
|
cout << " Yes." << endl;
|
||||||
|
else
|
||||||
|
cout << " No." << endl;
|
||||||
|
|
||||||
|
// Get the Test string
|
||||||
|
int count = 0;
|
||||||
|
string test_string;
|
||||||
|
if (argc == 4) {
|
||||||
|
test_string = argv[3];
|
||||||
|
} else {
|
||||||
|
test_string = "Testing.";
|
||||||
|
}
|
||||||
|
|
||||||
|
// Test the timeout, there should be 1 second between prints
|
||||||
|
cout << "Timeout == 1000ms, asking for 1 more byte than written." << endl;
|
||||||
|
while (count < 10) {
|
||||||
|
size_t bytes_wrote = my_serial.write(test_string);
|
||||||
|
|
||||||
|
string result = my_serial.read(test_string.length()+1);
|
||||||
|
|
||||||
|
cout << "Iteration: " << count << ", Bytes written: ";
|
||||||
|
cout << bytes_wrote << ", Bytes read: ";
|
||||||
|
cout << result.length() << ", String read: " << result << endl;
|
||||||
|
|
||||||
|
count += 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Test the timeout at 250ms
|
||||||
|
my_serial.setTimeout(serial::Timeout::max(), 250, 0, 250, 0);
|
||||||
|
count = 0;
|
||||||
|
cout << "Timeout == 250ms, asking for 1 more byte than written." << endl;
|
||||||
|
while (count < 10) {
|
||||||
|
size_t bytes_wrote = my_serial.write(test_string);
|
||||||
|
|
||||||
|
string result = my_serial.read(test_string.length()+1);
|
||||||
|
|
||||||
|
cout << "Iteration: " << count << ", Bytes written: ";
|
||||||
|
cout << bytes_wrote << ", Bytes read: ";
|
||||||
|
cout << result.length() << ", String read: " << result << endl;
|
||||||
|
|
||||||
|
count += 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Test the timeout at 250ms, but asking exactly for what was written
|
||||||
|
count = 0;
|
||||||
|
cout << "Timeout == 250ms, asking for exactly what was written." << endl;
|
||||||
|
while (count < 10) {
|
||||||
|
size_t bytes_wrote = my_serial.write(test_string);
|
||||||
|
|
||||||
|
string result = my_serial.read(test_string.length());
|
||||||
|
|
||||||
|
cout << "Iteration: " << count << ", Bytes written: ";
|
||||||
|
cout << bytes_wrote << ", Bytes read: ";
|
||||||
|
cout << result.length() << ", String read: " << result << endl;
|
||||||
|
|
||||||
|
count += 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Test the timeout at 250ms, but asking for 1 less than what was written
|
||||||
|
count = 0;
|
||||||
|
cout << "Timeout == 250ms, asking for 1 less than was written." << endl;
|
||||||
|
while (count < 10) {
|
||||||
|
size_t bytes_wrote = my_serial.write(test_string);
|
||||||
|
|
||||||
|
string result = my_serial.read(test_string.length()-1);
|
||||||
|
|
||||||
|
cout << "Iteration: " << count << ", Bytes written: ";
|
||||||
|
cout << bytes_wrote << ", Bytes read: ";
|
||||||
|
cout << result.length() << ", String read: " << result << endl;
|
||||||
|
|
||||||
|
count += 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(int argc, char **argv) {
|
||||||
|
try {
|
||||||
|
return run(argc, argv);
|
||||||
|
} catch (exception &e) {
|
||||||
|
cerr << "Unhandled Exception: " << e.what() << endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
221
scout_base/src/scout_sdk/src/third_party/serial/include/serial/impl/unix.h
vendored
Normal file
221
scout_base/src/scout_sdk/src/third_party/serial/include/serial/impl/unix.h
vendored
Normal file
@@ -0,0 +1,221 @@
|
|||||||
|
/*!
|
||||||
|
* \file serial/impl/unix.h
|
||||||
|
* \author William Woodall <wjwwood@gmail.com>
|
||||||
|
* \author John Harrison <ash@greaterthaninfinity.com>
|
||||||
|
* \version 0.1
|
||||||
|
*
|
||||||
|
* \section LICENSE
|
||||||
|
*
|
||||||
|
* The MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2012 William Woodall, John Harrison
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||||
|
* copy of this software and associated documentation files (the "Software"),
|
||||||
|
* to deal in the Software without restriction, including without limitation
|
||||||
|
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||||
|
* and/or sell copies of the Software, and to permit persons to whom the
|
||||||
|
* Software is furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||||
|
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||||
|
* DEALINGS IN THE SOFTWARE.
|
||||||
|
*
|
||||||
|
* \section DESCRIPTION
|
||||||
|
*
|
||||||
|
* This provides a unix based pimpl for the Serial class. This implementation is
|
||||||
|
* based off termios.h and uses select for multiplexing the IO ports.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if !defined(_WIN32)
|
||||||
|
|
||||||
|
#ifndef SERIAL_IMPL_UNIX_H
|
||||||
|
#define SERIAL_IMPL_UNIX_H
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
#include <pthread.h>
|
||||||
|
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
using std::size_t;
|
||||||
|
using std::string;
|
||||||
|
using std::invalid_argument;
|
||||||
|
|
||||||
|
using serial::SerialException;
|
||||||
|
using serial::IOException;
|
||||||
|
|
||||||
|
class MillisecondTimer {
|
||||||
|
public:
|
||||||
|
MillisecondTimer(const uint32_t millis);
|
||||||
|
int64_t remaining();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static timespec timespec_now();
|
||||||
|
timespec expiry;
|
||||||
|
};
|
||||||
|
|
||||||
|
class serial::Serial::SerialImpl {
|
||||||
|
public:
|
||||||
|
SerialImpl (const string &port,
|
||||||
|
unsigned long baudrate,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity,
|
||||||
|
stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
virtual ~SerialImpl ();
|
||||||
|
|
||||||
|
void
|
||||||
|
open ();
|
||||||
|
|
||||||
|
void
|
||||||
|
close ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
isOpen () const;
|
||||||
|
|
||||||
|
size_t
|
||||||
|
available ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
waitReadable (uint32_t timeout);
|
||||||
|
|
||||||
|
void
|
||||||
|
waitByteTimes (size_t count);
|
||||||
|
|
||||||
|
size_t
|
||||||
|
read (uint8_t *buf, size_t size = 1);
|
||||||
|
|
||||||
|
size_t
|
||||||
|
write (const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
void
|
||||||
|
flush ();
|
||||||
|
|
||||||
|
void
|
||||||
|
flushInput ();
|
||||||
|
|
||||||
|
void
|
||||||
|
flushOutput ();
|
||||||
|
|
||||||
|
void
|
||||||
|
sendBreak (int duration);
|
||||||
|
|
||||||
|
void
|
||||||
|
setBreak (bool level);
|
||||||
|
|
||||||
|
void
|
||||||
|
setRTS (bool level);
|
||||||
|
|
||||||
|
void
|
||||||
|
setDTR (bool level);
|
||||||
|
|
||||||
|
bool
|
||||||
|
waitForChange ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getCTS ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getDSR ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getRI ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getCD ();
|
||||||
|
|
||||||
|
void
|
||||||
|
setPort (const string &port);
|
||||||
|
|
||||||
|
string
|
||||||
|
getPort () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setTimeout (Timeout &timeout);
|
||||||
|
|
||||||
|
Timeout
|
||||||
|
getTimeout () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setBaudrate (unsigned long baudrate);
|
||||||
|
|
||||||
|
unsigned long
|
||||||
|
getBaudrate () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setBytesize (bytesize_t bytesize);
|
||||||
|
|
||||||
|
bytesize_t
|
||||||
|
getBytesize () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setParity (parity_t parity);
|
||||||
|
|
||||||
|
parity_t
|
||||||
|
getParity () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setStopbits (stopbits_t stopbits);
|
||||||
|
|
||||||
|
stopbits_t
|
||||||
|
getStopbits () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setFlowcontrol (flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
flowcontrol_t
|
||||||
|
getFlowcontrol () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
readLock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
readUnlock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
writeLock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
writeUnlock ();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void reconfigurePort ();
|
||||||
|
|
||||||
|
private:
|
||||||
|
string port_; // Path to the file descriptor
|
||||||
|
int fd_; // The current file descriptor
|
||||||
|
|
||||||
|
bool is_open_;
|
||||||
|
bool xonxoff_;
|
||||||
|
bool rtscts_;
|
||||||
|
|
||||||
|
Timeout timeout_; // Timeout for read operations
|
||||||
|
unsigned long baudrate_; // Baudrate
|
||||||
|
uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte
|
||||||
|
|
||||||
|
parity_t parity_; // Parity
|
||||||
|
bytesize_t bytesize_; // Size of the bytes
|
||||||
|
stopbits_t stopbits_; // Stop Bits
|
||||||
|
flowcontrol_t flowcontrol_; // Flow Control
|
||||||
|
|
||||||
|
// Mutex used to lock the read functions
|
||||||
|
pthread_mutex_t read_mutex;
|
||||||
|
// Mutex used to lock the write functions
|
||||||
|
pthread_mutex_t write_mutex;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // SERIAL_IMPL_UNIX_H
|
||||||
|
|
||||||
|
#endif // !defined(_WIN32)
|
||||||
207
scout_base/src/scout_sdk/src/third_party/serial/include/serial/impl/win.h
vendored
Normal file
207
scout_base/src/scout_sdk/src/third_party/serial/include/serial/impl/win.h
vendored
Normal file
@@ -0,0 +1,207 @@
|
|||||||
|
/*!
|
||||||
|
* \file serial/impl/windows.h
|
||||||
|
* \author William Woodall <wjwwood@gmail.com>
|
||||||
|
* \author John Harrison <ash@greaterthaninfinity.com>
|
||||||
|
* \version 0.1
|
||||||
|
*
|
||||||
|
* \section LICENSE
|
||||||
|
*
|
||||||
|
* The MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2012 William Woodall, John Harrison
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||||
|
* copy of this software and associated documentation files (the "Software"),
|
||||||
|
* to deal in the Software without restriction, including without limitation
|
||||||
|
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||||
|
* and/or sell copies of the Software, and to permit persons to whom the
|
||||||
|
* Software is furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||||
|
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||||
|
* DEALINGS IN THE SOFTWARE.
|
||||||
|
*
|
||||||
|
* \section DESCRIPTION
|
||||||
|
*
|
||||||
|
* This provides a windows implementation of the Serial class interface.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
#ifndef SERIAL_IMPL_WINDOWS_H
|
||||||
|
#define SERIAL_IMPL_WINDOWS_H
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
#include "windows.h"
|
||||||
|
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
using std::string;
|
||||||
|
using std::wstring;
|
||||||
|
using std::invalid_argument;
|
||||||
|
|
||||||
|
using serial::SerialException;
|
||||||
|
using serial::IOException;
|
||||||
|
|
||||||
|
class serial::Serial::SerialImpl {
|
||||||
|
public:
|
||||||
|
SerialImpl (const string &port,
|
||||||
|
unsigned long baudrate,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity,
|
||||||
|
stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
virtual ~SerialImpl ();
|
||||||
|
|
||||||
|
void
|
||||||
|
open ();
|
||||||
|
|
||||||
|
void
|
||||||
|
close ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
isOpen () const;
|
||||||
|
|
||||||
|
size_t
|
||||||
|
available ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
waitReadable (uint32_t timeout);
|
||||||
|
|
||||||
|
void
|
||||||
|
waitByteTimes (size_t count);
|
||||||
|
|
||||||
|
size_t
|
||||||
|
read (uint8_t *buf, size_t size = 1);
|
||||||
|
|
||||||
|
size_t
|
||||||
|
write (const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
void
|
||||||
|
flush ();
|
||||||
|
|
||||||
|
void
|
||||||
|
flushInput ();
|
||||||
|
|
||||||
|
void
|
||||||
|
flushOutput ();
|
||||||
|
|
||||||
|
void
|
||||||
|
sendBreak (int duration);
|
||||||
|
|
||||||
|
void
|
||||||
|
setBreak (bool level);
|
||||||
|
|
||||||
|
void
|
||||||
|
setRTS (bool level);
|
||||||
|
|
||||||
|
void
|
||||||
|
setDTR (bool level);
|
||||||
|
|
||||||
|
bool
|
||||||
|
waitForChange ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getCTS ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getDSR ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getRI ();
|
||||||
|
|
||||||
|
bool
|
||||||
|
getCD ();
|
||||||
|
|
||||||
|
void
|
||||||
|
setPort (const string &port);
|
||||||
|
|
||||||
|
string
|
||||||
|
getPort () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setTimeout (Timeout &timeout);
|
||||||
|
|
||||||
|
Timeout
|
||||||
|
getTimeout () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setBaudrate (unsigned long baudrate);
|
||||||
|
|
||||||
|
unsigned long
|
||||||
|
getBaudrate () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setBytesize (bytesize_t bytesize);
|
||||||
|
|
||||||
|
bytesize_t
|
||||||
|
getBytesize () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setParity (parity_t parity);
|
||||||
|
|
||||||
|
parity_t
|
||||||
|
getParity () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setStopbits (stopbits_t stopbits);
|
||||||
|
|
||||||
|
stopbits_t
|
||||||
|
getStopbits () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
setFlowcontrol (flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
flowcontrol_t
|
||||||
|
getFlowcontrol () const;
|
||||||
|
|
||||||
|
void
|
||||||
|
readLock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
readUnlock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
writeLock ();
|
||||||
|
|
||||||
|
void
|
||||||
|
writeUnlock ();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void reconfigurePort ();
|
||||||
|
|
||||||
|
private:
|
||||||
|
wstring port_; // Path to the file descriptor
|
||||||
|
HANDLE fd_;
|
||||||
|
|
||||||
|
bool is_open_;
|
||||||
|
|
||||||
|
Timeout timeout_; // Timeout for read operations
|
||||||
|
unsigned long baudrate_; // Baudrate
|
||||||
|
|
||||||
|
parity_t parity_; // Parity
|
||||||
|
bytesize_t bytesize_; // Size of the bytes
|
||||||
|
stopbits_t stopbits_; // Stop Bits
|
||||||
|
flowcontrol_t flowcontrol_; // Flow Control
|
||||||
|
|
||||||
|
// Mutex used to lock the read functions
|
||||||
|
HANDLE read_mutex;
|
||||||
|
// Mutex used to lock the write functions
|
||||||
|
HANDLE write_mutex;
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // SERIAL_IMPL_WINDOWS_H
|
||||||
|
|
||||||
|
#endif // if defined(_WIN32)
|
||||||
775
scout_base/src/scout_sdk/src/third_party/serial/include/serial/serial.h
vendored
Normal file
775
scout_base/src/scout_sdk/src/third_party/serial/include/serial/serial.h
vendored
Normal file
@@ -0,0 +1,775 @@
|
|||||||
|
/*!
|
||||||
|
* \file serial/serial.h
|
||||||
|
* \author William Woodall <wjwwood@gmail.com>
|
||||||
|
* \author John Harrison <ash.gti@gmail.com>
|
||||||
|
* \version 0.1
|
||||||
|
*
|
||||||
|
* \section LICENSE
|
||||||
|
*
|
||||||
|
* The MIT License
|
||||||
|
*
|
||||||
|
* Copyright (c) 2012 William Woodall
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||||
|
* copy of this software and associated documentation files (the "Software"),
|
||||||
|
* to deal in the Software without restriction, including without limitation
|
||||||
|
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||||
|
* and/or sell copies of the Software, and to permit persons to whom the
|
||||||
|
* Software is furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||||
|
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||||
|
* DEALINGS IN THE SOFTWARE.
|
||||||
|
*
|
||||||
|
* \section DESCRIPTION
|
||||||
|
*
|
||||||
|
* This provides a cross platform interface for interacting with Serial Ports.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SERIAL_H
|
||||||
|
#define SERIAL_H
|
||||||
|
|
||||||
|
#include <limits>
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
#include <sstream>
|
||||||
|
#include <exception>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <serial/v8stdint.h>
|
||||||
|
|
||||||
|
#define THROW(exceptionClass, message) throw exceptionClass(__FILE__, \
|
||||||
|
__LINE__, (message) )
|
||||||
|
|
||||||
|
namespace serial {
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible bytesizes for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
fivebits = 5,
|
||||||
|
sixbits = 6,
|
||||||
|
sevenbits = 7,
|
||||||
|
eightbits = 8
|
||||||
|
} bytesize_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible parity types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
parity_none = 0,
|
||||||
|
parity_odd = 1,
|
||||||
|
parity_even = 2,
|
||||||
|
parity_mark = 3,
|
||||||
|
parity_space = 4
|
||||||
|
} parity_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible stopbit types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
stopbits_one = 1,
|
||||||
|
stopbits_two = 2,
|
||||||
|
stopbits_one_point_five
|
||||||
|
} stopbits_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Enumeration defines the possible flowcontrol types for the serial port.
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
flowcontrol_none = 0,
|
||||||
|
flowcontrol_software,
|
||||||
|
flowcontrol_hardware
|
||||||
|
} flowcontrol_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Structure for setting the timeout of the serial port, times are
|
||||||
|
* in milliseconds.
|
||||||
|
*
|
||||||
|
* In order to disable the interbyte timeout, set it to Timeout::max().
|
||||||
|
*/
|
||||||
|
struct Timeout {
|
||||||
|
#ifdef max
|
||||||
|
# undef max
|
||||||
|
#endif
|
||||||
|
static uint32_t max() {return std::numeric_limits<uint32_t>::max();}
|
||||||
|
/*!
|
||||||
|
* Convenience function to generate Timeout structs using a
|
||||||
|
* single absolute timeout.
|
||||||
|
*
|
||||||
|
* \param timeout A long that defines the time in milliseconds until a
|
||||||
|
* timeout occurs after a call to read or write is made.
|
||||||
|
*
|
||||||
|
* \return Timeout struct that represents this simple timeout provided.
|
||||||
|
*/
|
||||||
|
static Timeout simpleTimeout(uint32_t timeout) {
|
||||||
|
return Timeout(max(), timeout, 0, timeout, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*! Number of milliseconds between bytes received to timeout on. */
|
||||||
|
uint32_t inter_byte_timeout;
|
||||||
|
/*! A constant number of milliseconds to wait after calling read. */
|
||||||
|
uint32_t read_timeout_constant;
|
||||||
|
/*! A multiplier against the number of requested bytes to wait after
|
||||||
|
* calling read.
|
||||||
|
*/
|
||||||
|
uint32_t read_timeout_multiplier;
|
||||||
|
/*! A constant number of milliseconds to wait after calling write. */
|
||||||
|
uint32_t write_timeout_constant;
|
||||||
|
/*! A multiplier against the number of requested bytes to wait after
|
||||||
|
* calling write.
|
||||||
|
*/
|
||||||
|
uint32_t write_timeout_multiplier;
|
||||||
|
|
||||||
|
explicit Timeout (uint32_t inter_byte_timeout_=0,
|
||||||
|
uint32_t read_timeout_constant_=0,
|
||||||
|
uint32_t read_timeout_multiplier_=0,
|
||||||
|
uint32_t write_timeout_constant_=0,
|
||||||
|
uint32_t write_timeout_multiplier_=0)
|
||||||
|
: inter_byte_timeout(inter_byte_timeout_),
|
||||||
|
read_timeout_constant(read_timeout_constant_),
|
||||||
|
read_timeout_multiplier(read_timeout_multiplier_),
|
||||||
|
write_timeout_constant(write_timeout_constant_),
|
||||||
|
write_timeout_multiplier(write_timeout_multiplier_)
|
||||||
|
{}
|
||||||
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Class that provides a portable serial port interface.
|
||||||
|
*/
|
||||||
|
class Serial {
|
||||||
|
public:
|
||||||
|
/*!
|
||||||
|
* Creates a Serial object and opens the port if a port is specified,
|
||||||
|
* otherwise it remains closed until serial::Serial::open is called.
|
||||||
|
*
|
||||||
|
* \param port A std::string containing the address of the serial port,
|
||||||
|
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||||
|
* on Linux.
|
||||||
|
*
|
||||||
|
* \param baudrate An unsigned 32-bit integer that represents the baudrate
|
||||||
|
*
|
||||||
|
* \param timeout A serial::Timeout struct that defines the timeout
|
||||||
|
* conditions for the serial port. \see serial::Timeout
|
||||||
|
*
|
||||||
|
* \param bytesize Size of each byte in the serial transmission of data,
|
||||||
|
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
|
||||||
|
* eightbits
|
||||||
|
*
|
||||||
|
* \param parity Method of parity, default is parity_none, possible values
|
||||||
|
* are: parity_none, parity_odd, parity_even
|
||||||
|
*
|
||||||
|
* \param stopbits Number of stop bits used, default is stopbits_one,
|
||||||
|
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
|
||||||
|
*
|
||||||
|
* \param flowcontrol Type of flowcontrol used, default is
|
||||||
|
* flowcontrol_none, possible values are: flowcontrol_none,
|
||||||
|
* flowcontrol_software, flowcontrol_hardware
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::IOException
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
Serial (const std::string &port = "",
|
||||||
|
uint32_t baudrate = 9600,
|
||||||
|
Timeout timeout = Timeout(),
|
||||||
|
bytesize_t bytesize = eightbits,
|
||||||
|
parity_t parity = parity_none,
|
||||||
|
stopbits_t stopbits = stopbits_one,
|
||||||
|
flowcontrol_t flowcontrol = flowcontrol_none);
|
||||||
|
|
||||||
|
/*! Destructor */
|
||||||
|
virtual ~Serial ();
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Opens the serial port as long as the port is set and the port isn't
|
||||||
|
* already open.
|
||||||
|
*
|
||||||
|
* If the port is provided to the constructor then an explicit call to open
|
||||||
|
* is not needed.
|
||||||
|
*
|
||||||
|
* \see Serial::Serial
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
* \throw serial::SerialException
|
||||||
|
* \throw serial::IOException
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
open ();
|
||||||
|
|
||||||
|
/*! Gets the open status of the serial port.
|
||||||
|
*
|
||||||
|
* \return Returns true if the port is open, false otherwise.
|
||||||
|
*/
|
||||||
|
bool
|
||||||
|
isOpen () const;
|
||||||
|
|
||||||
|
/*! Closes the serial port. */
|
||||||
|
void
|
||||||
|
close ();
|
||||||
|
|
||||||
|
/*! Return the number of characters in the buffer. */
|
||||||
|
size_t
|
||||||
|
available ();
|
||||||
|
|
||||||
|
/*! Block until there is serial data to read or read_timeout_constant
|
||||||
|
* number of milliseconds have elapsed. The return value is true when
|
||||||
|
* the function exits with the port in a readable state, false otherwise
|
||||||
|
* (due to timeout or select interruption). */
|
||||||
|
bool
|
||||||
|
waitReadable ();
|
||||||
|
|
||||||
|
/*! Block for a period of time corresponding to the transmission time of
|
||||||
|
* count characters at present serial settings. This may be used in con-
|
||||||
|
* junction with waitReadable to read larger blocks of data from the
|
||||||
|
* port. */
|
||||||
|
void
|
||||||
|
waitByteTimes (size_t count);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a given buffer.
|
||||||
|
*
|
||||||
|
* The read function will return in one of three cases:
|
||||||
|
* * The number of requested bytes was read.
|
||||||
|
* * In this case the number of bytes requested will match the size_t
|
||||||
|
* returned by read.
|
||||||
|
* * A timeout occurred, in this case the number of bytes read will not
|
||||||
|
* match the amount requested, but no exception will be thrown. One of
|
||||||
|
* two possible timeouts occurred:
|
||||||
|
* * The inter byte timeout expired, this means that number of
|
||||||
|
* milliseconds elapsed between receiving bytes from the serial port
|
||||||
|
* exceeded the inter byte timeout.
|
||||||
|
* * The total timeout expired, which is calculated by multiplying the
|
||||||
|
* read timeout multiplier by the number of requested bytes and then
|
||||||
|
* added to the read timeout constant. If that total number of
|
||||||
|
* milliseconds elapses after the initial call to read a timeout will
|
||||||
|
* occur.
|
||||||
|
* * An exception occurred, in this case an actual exception will be thrown.
|
||||||
|
*
|
||||||
|
* \param buffer An uint8_t array of at least the requested size.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
read (uint8_t *buffer, size_t size);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a give buffer.
|
||||||
|
*
|
||||||
|
* \param buffer A reference to a std::vector of uint8_t.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
read (std::vector<uint8_t> &buffer, size_t size = 1);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port into a give buffer.
|
||||||
|
*
|
||||||
|
* \param buffer A reference to a std::string.
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read as a result of the
|
||||||
|
* call to read.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
read (std::string &buffer, size_t size = 1);
|
||||||
|
|
||||||
|
/*! Read a given amount of bytes from the serial port and return a string
|
||||||
|
* containing the data.
|
||||||
|
*
|
||||||
|
* \param size A size_t defining how many bytes to be read.
|
||||||
|
*
|
||||||
|
* \return A std::string containing the data read from the port.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
std::string
|
||||||
|
read (size_t size = 1);
|
||||||
|
|
||||||
|
/*! Reads in a line or until a given delimiter has been processed.
|
||||||
|
*
|
||||||
|
* Reads from the serial port until a single line has been read.
|
||||||
|
*
|
||||||
|
* \param buffer A std::string reference used to store the data.
|
||||||
|
* \param size A maximum length of a line, defaults to 65536 (2^16)
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes read.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
readline (std::string &buffer, size_t size = 65536, std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Reads in a line or until a given delimiter has been processed.
|
||||||
|
*
|
||||||
|
* Reads from the serial port until a single line has been read.
|
||||||
|
*
|
||||||
|
* \param size A maximum length of a line, defaults to 65536 (2^16)
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A std::string containing the line.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
std::string
|
||||||
|
readline (size_t size = 65536, std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Reads in multiple lines until the serial port times out.
|
||||||
|
*
|
||||||
|
* This requires a timeout > 0 before it can be run. It will read until a
|
||||||
|
* timeout occurs and return a list of strings.
|
||||||
|
*
|
||||||
|
* \param size A maximum length of combined lines, defaults to 65536 (2^16)
|
||||||
|
*
|
||||||
|
* \param eol A string to match against for the EOL.
|
||||||
|
*
|
||||||
|
* \return A vector<string> containing the lines.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
*/
|
||||||
|
std::vector<std::string>
|
||||||
|
readlines (size_t size = 65536, std::string eol = "\n");
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \param size A size_t that indicates how many bytes should be written from
|
||||||
|
* the given data buffer.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
* \throw serial::IOException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
write (const uint8_t *data, size_t size);
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
* \throw serial::IOException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
write (const std::vector<uint8_t> &data);
|
||||||
|
|
||||||
|
/*! Write a string to the serial port.
|
||||||
|
*
|
||||||
|
* \param data A const reference containing the data to be written
|
||||||
|
* to the serial port.
|
||||||
|
*
|
||||||
|
* \return A size_t representing the number of bytes actually written to
|
||||||
|
* the serial port.
|
||||||
|
*
|
||||||
|
* \throw serial::PortNotOpenedException
|
||||||
|
* \throw serial::SerialException
|
||||||
|
* \throw serial::IOException
|
||||||
|
*/
|
||||||
|
size_t
|
||||||
|
write (const std::string &data);
|
||||||
|
|
||||||
|
/*! Sets the serial port identifier.
|
||||||
|
*
|
||||||
|
* \param port A const std::string reference containing the address of the
|
||||||
|
* serial port, which would be something like 'COM1' on Windows and
|
||||||
|
* '/dev/ttyS0' on Linux.
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setPort (const std::string &port);
|
||||||
|
|
||||||
|
/*! Gets the serial port identifier.
|
||||||
|
*
|
||||||
|
* \see Serial::setPort
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
std::string
|
||||||
|
getPort () const;
|
||||||
|
|
||||||
|
/*! Sets the timeout for reads and writes using the Timeout struct.
|
||||||
|
*
|
||||||
|
* There are two timeout conditions described here:
|
||||||
|
* * The inter byte timeout:
|
||||||
|
* * The inter_byte_timeout component of serial::Timeout defines the
|
||||||
|
* maximum amount of time, in milliseconds, between receiving bytes on
|
||||||
|
* the serial port that can pass before a timeout occurs. Setting this
|
||||||
|
* to zero will prevent inter byte timeouts from occurring.
|
||||||
|
* * Total time timeout:
|
||||||
|
* * The constant and multiplier component of this timeout condition,
|
||||||
|
* for both read and write, are defined in serial::Timeout. This
|
||||||
|
* timeout occurs if the total time since the read or write call was
|
||||||
|
* made exceeds the specified time in milliseconds.
|
||||||
|
* * The limit is defined by multiplying the multiplier component by the
|
||||||
|
* number of requested bytes and adding that product to the constant
|
||||||
|
* component. In this way if you want a read call, for example, to
|
||||||
|
* timeout after exactly one second regardless of the number of bytes
|
||||||
|
* you asked for then set the read_timeout_constant component of
|
||||||
|
* serial::Timeout to 1000 and the read_timeout_multiplier to zero.
|
||||||
|
* This timeout condition can be used in conjunction with the inter
|
||||||
|
* byte timeout condition with out any problems, timeout will simply
|
||||||
|
* occur when one of the two timeout conditions is met. This allows
|
||||||
|
* users to have maximum control over the trade-off between
|
||||||
|
* responsiveness and efficiency.
|
||||||
|
*
|
||||||
|
* Read and write functions will return in one of three cases. When the
|
||||||
|
* reading or writing is complete, when a timeout occurs, or when an
|
||||||
|
* exception occurs.
|
||||||
|
*
|
||||||
|
* A timeout of 0 enables non-blocking mode.
|
||||||
|
*
|
||||||
|
* \param timeout A serial::Timeout struct containing the inter byte
|
||||||
|
* timeout, and the read and write timeout constants and multipliers.
|
||||||
|
*
|
||||||
|
* \see serial::Timeout
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setTimeout (Timeout &timeout);
|
||||||
|
|
||||||
|
/*! Sets the timeout for reads and writes. */
|
||||||
|
void
|
||||||
|
setTimeout (uint32_t inter_byte_timeout, uint32_t read_timeout_constant,
|
||||||
|
uint32_t read_timeout_multiplier, uint32_t write_timeout_constant,
|
||||||
|
uint32_t write_timeout_multiplier)
|
||||||
|
{
|
||||||
|
Timeout timeout(inter_byte_timeout, read_timeout_constant,
|
||||||
|
read_timeout_multiplier, write_timeout_constant,
|
||||||
|
write_timeout_multiplier);
|
||||||
|
return setTimeout(timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*! Gets the timeout for reads in seconds.
|
||||||
|
*
|
||||||
|
* \return A Timeout struct containing the inter_byte_timeout, and read
|
||||||
|
* and write timeout constants and multipliers.
|
||||||
|
*
|
||||||
|
* \see Serial::setTimeout
|
||||||
|
*/
|
||||||
|
Timeout
|
||||||
|
getTimeout () const;
|
||||||
|
|
||||||
|
/*! Sets the baudrate for the serial port.
|
||||||
|
*
|
||||||
|
* Possible baudrates depends on the system but some safe baudrates include:
|
||||||
|
* 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000,
|
||||||
|
* 57600, 115200
|
||||||
|
* Some other baudrates that are supported by some comports:
|
||||||
|
* 128000, 153600, 230400, 256000, 460800, 500000, 921600
|
||||||
|
*
|
||||||
|
* \param baudrate An integer that sets the baud rate for the serial port.
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setBaudrate (uint32_t baudrate);
|
||||||
|
|
||||||
|
/*! Gets the baudrate for the serial port.
|
||||||
|
*
|
||||||
|
* \return An integer that sets the baud rate for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setBaudrate
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
uint32_t
|
||||||
|
getBaudrate () const;
|
||||||
|
|
||||||
|
/*! Sets the bytesize for the serial port.
|
||||||
|
*
|
||||||
|
* \param bytesize Size of each byte in the serial transmission of data,
|
||||||
|
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
|
||||||
|
* eightbits
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setBytesize (bytesize_t bytesize);
|
||||||
|
|
||||||
|
/*! Gets the bytesize for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setBytesize
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
bytesize_t
|
||||||
|
getBytesize () const;
|
||||||
|
|
||||||
|
/*! Sets the parity for the serial port.
|
||||||
|
*
|
||||||
|
* \param parity Method of parity, default is parity_none, possible values
|
||||||
|
* are: parity_none, parity_odd, parity_even
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setParity (parity_t parity);
|
||||||
|
|
||||||
|
/*! Gets the parity for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setParity
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
parity_t
|
||||||
|
getParity () const;
|
||||||
|
|
||||||
|
/*! Sets the stopbits for the serial port.
|
||||||
|
*
|
||||||
|
* \param stopbits Number of stop bits used, default is stopbits_one,
|
||||||
|
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setStopbits (stopbits_t stopbits);
|
||||||
|
|
||||||
|
/*! Gets the stopbits for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setStopbits
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
stopbits_t
|
||||||
|
getStopbits () const;
|
||||||
|
|
||||||
|
/*! Sets the flow control for the serial port.
|
||||||
|
*
|
||||||
|
* \param flowcontrol Type of flowcontrol used, default is flowcontrol_none,
|
||||||
|
* possible values are: flowcontrol_none, flowcontrol_software,
|
||||||
|
* flowcontrol_hardware
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
setFlowcontrol (flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
/*! Gets the flow control for the serial port.
|
||||||
|
*
|
||||||
|
* \see Serial::setFlowcontrol
|
||||||
|
*
|
||||||
|
* \throw std::invalid_argument
|
||||||
|
*/
|
||||||
|
flowcontrol_t
|
||||||
|
getFlowcontrol () const;
|
||||||
|
|
||||||
|
/*! Flush the input and output buffers */
|
||||||
|
void
|
||||||
|
flush ();
|
||||||
|
|
||||||
|
/*! Flush only the input buffer */
|
||||||
|
void
|
||||||
|
flushInput ();
|
||||||
|
|
||||||
|
/*! Flush only the output buffer */
|
||||||
|
void
|
||||||
|
flushOutput ();
|
||||||
|
|
||||||
|
/*! Sends the RS-232 break signal. See tcsendbreak(3). */
|
||||||
|
void
|
||||||
|
sendBreak (int duration);
|
||||||
|
|
||||||
|
/*! Set the break condition to a given level. Defaults to true. */
|
||||||
|
void
|
||||||
|
setBreak (bool level = true);
|
||||||
|
|
||||||
|
/*! Set the RTS handshaking line to the given level. Defaults to true. */
|
||||||
|
void
|
||||||
|
setRTS (bool level = true);
|
||||||
|
|
||||||
|
/*! Set the DTR handshaking line to the given level. Defaults to true. */
|
||||||
|
void
|
||||||
|
setDTR (bool level = true);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Blocks until CTS, DSR, RI, CD changes or something interrupts it.
|
||||||
|
*
|
||||||
|
* Can throw an exception if an error occurs while waiting.
|
||||||
|
* You can check the status of CTS, DSR, RI, and CD once this returns.
|
||||||
|
* Uses TIOCMIWAIT via ioctl if available (mostly only on Linux) with a
|
||||||
|
* resolution of less than +-1ms and as good as +-0.2ms. Otherwise a
|
||||||
|
* polling method is used which can give +-2ms.
|
||||||
|
*
|
||||||
|
* \return Returns true if one of the lines changed, false if something else
|
||||||
|
* occurred.
|
||||||
|
*
|
||||||
|
* \throw SerialException
|
||||||
|
*/
|
||||||
|
bool
|
||||||
|
waitForChange ();
|
||||||
|
|
||||||
|
/*! Returns the current status of the CTS line. */
|
||||||
|
bool
|
||||||
|
getCTS ();
|
||||||
|
|
||||||
|
/*! Returns the current status of the DSR line. */
|
||||||
|
bool
|
||||||
|
getDSR ();
|
||||||
|
|
||||||
|
/*! Returns the current status of the RI line. */
|
||||||
|
bool
|
||||||
|
getRI ();
|
||||||
|
|
||||||
|
/*! Returns the current status of the CD line. */
|
||||||
|
bool
|
||||||
|
getCD ();
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
Serial(const Serial&);
|
||||||
|
Serial& operator=(const Serial&);
|
||||||
|
|
||||||
|
// Pimpl idiom, d_pointer
|
||||||
|
class SerialImpl;
|
||||||
|
SerialImpl *pimpl_;
|
||||||
|
|
||||||
|
// Scoped Lock Classes
|
||||||
|
class ScopedReadLock;
|
||||||
|
class ScopedWriteLock;
|
||||||
|
|
||||||
|
// Read common function
|
||||||
|
size_t
|
||||||
|
read_ (uint8_t *buffer, size_t size);
|
||||||
|
// Write common function
|
||||||
|
size_t
|
||||||
|
write_ (const uint8_t *data, size_t length);
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
class SerialException : public std::exception
|
||||||
|
{
|
||||||
|
// Disable copy constructors
|
||||||
|
SerialException& operator=(const SerialException&);
|
||||||
|
std::string e_what_;
|
||||||
|
public:
|
||||||
|
SerialException (const char *description) {
|
||||||
|
std::stringstream ss;
|
||||||
|
ss << "SerialException " << description << " failed.";
|
||||||
|
e_what_ = ss.str();
|
||||||
|
}
|
||||||
|
SerialException (const SerialException& other) : e_what_(other.e_what_) {}
|
||||||
|
virtual ~SerialException() throw() {}
|
||||||
|
virtual const char* what () const throw () {
|
||||||
|
return e_what_.c_str();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class IOException : public std::exception
|
||||||
|
{
|
||||||
|
// Disable copy constructors
|
||||||
|
IOException& operator=(const IOException&);
|
||||||
|
std::string file_;
|
||||||
|
int line_;
|
||||||
|
std::string e_what_;
|
||||||
|
int errno_;
|
||||||
|
public:
|
||||||
|
explicit IOException (std::string file, int line, int errnum)
|
||||||
|
: file_(file), line_(line), errno_(errnum) {
|
||||||
|
std::stringstream ss;
|
||||||
|
#if defined(_WIN32) && !defined(__MINGW32__)
|
||||||
|
char error_str [1024];
|
||||||
|
strerror_s(error_str, 1024, errnum);
|
||||||
|
#else
|
||||||
|
char * error_str = strerror(errnum);
|
||||||
|
#endif
|
||||||
|
ss << "IO Exception (" << errno_ << "): " << error_str;
|
||||||
|
ss << ", file " << file_ << ", line " << line_ << ".";
|
||||||
|
e_what_ = ss.str();
|
||||||
|
}
|
||||||
|
explicit IOException (std::string file, int line, const char * description)
|
||||||
|
: file_(file), line_(line), errno_(0) {
|
||||||
|
std::stringstream ss;
|
||||||
|
ss << "IO Exception: " << description;
|
||||||
|
ss << ", file " << file_ << ", line " << line_ << ".";
|
||||||
|
e_what_ = ss.str();
|
||||||
|
}
|
||||||
|
virtual ~IOException() throw() {}
|
||||||
|
IOException (const IOException& other) : line_(other.line_), e_what_(other.e_what_), errno_(other.errno_) {}
|
||||||
|
|
||||||
|
int getErrorNumber () const { return errno_; }
|
||||||
|
|
||||||
|
virtual const char* what () const throw () {
|
||||||
|
return e_what_.c_str();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
class PortNotOpenedException : public std::exception
|
||||||
|
{
|
||||||
|
// Disable copy constructors
|
||||||
|
const PortNotOpenedException& operator=(PortNotOpenedException);
|
||||||
|
std::string e_what_;
|
||||||
|
public:
|
||||||
|
PortNotOpenedException (const char * description) {
|
||||||
|
std::stringstream ss;
|
||||||
|
ss << "PortNotOpenedException " << description << " failed.";
|
||||||
|
e_what_ = ss.str();
|
||||||
|
}
|
||||||
|
PortNotOpenedException (const PortNotOpenedException& other) : e_what_(other.e_what_) {}
|
||||||
|
virtual ~PortNotOpenedException() throw() {}
|
||||||
|
virtual const char* what () const throw () {
|
||||||
|
return e_what_.c_str();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* Structure that describes a serial device.
|
||||||
|
*/
|
||||||
|
struct PortInfo {
|
||||||
|
|
||||||
|
/*! Address of the serial port (this can be passed to the constructor of Serial). */
|
||||||
|
std::string port;
|
||||||
|
|
||||||
|
/*! Human readable description of serial device if available. */
|
||||||
|
std::string description;
|
||||||
|
|
||||||
|
/*! Hardware ID (e.g. VID:PID of USB serial devices) or "n/a" if not available. */
|
||||||
|
std::string hardware_id;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Lists the serial ports available on the system
|
||||||
|
*
|
||||||
|
* Returns a vector of available serial ports, each represented
|
||||||
|
* by a serial::PortInfo data structure:
|
||||||
|
*
|
||||||
|
* \return vector of serial::PortInfo.
|
||||||
|
*/
|
||||||
|
std::vector<PortInfo>
|
||||||
|
list_ports();
|
||||||
|
|
||||||
|
} // namespace serial
|
||||||
|
|
||||||
|
#endif
|
||||||
57
scout_base/src/scout_sdk/src/third_party/serial/include/serial/v8stdint.h
vendored
Normal file
57
scout_base/src/scout_sdk/src/third_party/serial/include/serial/v8stdint.h
vendored
Normal file
@@ -0,0 +1,57 @@
|
|||||||
|
// This header is from the v8 google project:
|
||||||
|
// http://code.google.com/p/v8/source/browse/trunk/include/v8stdint.h
|
||||||
|
|
||||||
|
// Copyright 2012 the V8 project authors. All rights reserved.
|
||||||
|
// Redistribution and use in source and binary forms, with or without
|
||||||
|
// modification, are permitted provided that the following conditions are
|
||||||
|
// met:
|
||||||
|
//
|
||||||
|
// * Redistributions of source code must retain the above copyright
|
||||||
|
// notice, this list of conditions and the following disclaimer.
|
||||||
|
// * Redistributions in binary form must reproduce the above
|
||||||
|
// copyright notice, this list of conditions and the following
|
||||||
|
// disclaimer in the documentation and/or other materials provided
|
||||||
|
// with the distribution.
|
||||||
|
// * Neither the name of Google Inc. nor the names of its
|
||||||
|
// contributors may be used to endorse or promote products derived
|
||||||
|
// from this software without specific prior written permission.
|
||||||
|
//
|
||||||
|
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
|
||||||
|
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
|
||||||
|
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||||
|
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||||
|
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||||
|
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
|
||||||
|
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||||
|
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
|
||||||
|
// Load definitions of standard types.
|
||||||
|
|
||||||
|
#ifndef V8STDINT_H_
|
||||||
|
#define V8STDINT_H_
|
||||||
|
|
||||||
|
#include <stddef.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#if defined(_WIN32) && !defined(__MINGW32__)
|
||||||
|
|
||||||
|
typedef signed char int8_t;
|
||||||
|
typedef unsigned char uint8_t;
|
||||||
|
typedef short int16_t; // NOLINT
|
||||||
|
typedef unsigned short uint16_t; // NOLINT
|
||||||
|
typedef int int32_t;
|
||||||
|
typedef unsigned int uint32_t;
|
||||||
|
typedef __int64 int64_t;
|
||||||
|
typedef unsigned __int64 uint64_t;
|
||||||
|
// intptr_t and friends are defined in crtdefs.h through stdio.h.
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // V8STDINT_H_
|
||||||
335
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_linux.cc
vendored
Normal file
335
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_linux.cc
vendored
Normal file
@@ -0,0 +1,335 @@
|
|||||||
|
#if defined(__linux__)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Copyright (c) 2014 Craig Lilley <cralilley@gmail.com>
|
||||||
|
* This software is made available under the terms of the MIT licence.
|
||||||
|
* A copy of the licence can be obtained from:
|
||||||
|
* http://opensource.org/licenses/MIT
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <sstream>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <iostream>
|
||||||
|
#include <fstream>
|
||||||
|
#include <cstdio>
|
||||||
|
#include <cstdarg>
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
#include <glob.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
using serial::PortInfo;
|
||||||
|
using std::istringstream;
|
||||||
|
using std::ifstream;
|
||||||
|
using std::getline;
|
||||||
|
using std::vector;
|
||||||
|
using std::string;
|
||||||
|
using std::cout;
|
||||||
|
using std::endl;
|
||||||
|
|
||||||
|
static vector<string> glob(const vector<string>& patterns);
|
||||||
|
static string basename(const string& path);
|
||||||
|
static string dirname(const string& path);
|
||||||
|
static bool path_exists(const string& path);
|
||||||
|
static string realpath(const string& path);
|
||||||
|
static string usb_sysfs_friendly_name(const string& sys_usb_path);
|
||||||
|
static vector<string> get_sysfs_info(const string& device_path);
|
||||||
|
static string read_line(const string& file);
|
||||||
|
static string usb_sysfs_hw_string(const string& sysfs_path);
|
||||||
|
static string format(const char* format, ...);
|
||||||
|
|
||||||
|
vector<string>
|
||||||
|
glob(const vector<string>& patterns)
|
||||||
|
{
|
||||||
|
vector<string> paths_found;
|
||||||
|
|
||||||
|
if(patterns.size() == 0)
|
||||||
|
return paths_found;
|
||||||
|
|
||||||
|
glob_t glob_results;
|
||||||
|
|
||||||
|
int glob_retval = glob(patterns[0].c_str(), 0, NULL, &glob_results);
|
||||||
|
|
||||||
|
vector<string>::const_iterator iter = patterns.begin();
|
||||||
|
|
||||||
|
while(++iter != patterns.end())
|
||||||
|
{
|
||||||
|
glob_retval = glob(iter->c_str(), GLOB_APPEND, NULL, &glob_results);
|
||||||
|
}
|
||||||
|
|
||||||
|
for(int path_index = 0; path_index < glob_results.gl_pathc; path_index++)
|
||||||
|
{
|
||||||
|
paths_found.push_back(glob_results.gl_pathv[path_index]);
|
||||||
|
}
|
||||||
|
|
||||||
|
globfree(&glob_results);
|
||||||
|
|
||||||
|
return paths_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
basename(const string& path)
|
||||||
|
{
|
||||||
|
size_t pos = path.rfind("/");
|
||||||
|
|
||||||
|
if(pos == std::string::npos)
|
||||||
|
return path;
|
||||||
|
|
||||||
|
return string(path, pos+1, string::npos);
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
dirname(const string& path)
|
||||||
|
{
|
||||||
|
size_t pos = path.rfind("/");
|
||||||
|
|
||||||
|
if(pos == std::string::npos)
|
||||||
|
return path;
|
||||||
|
else if(pos == 0)
|
||||||
|
return "/";
|
||||||
|
|
||||||
|
return string(path, 0, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
path_exists(const string& path)
|
||||||
|
{
|
||||||
|
struct stat sb;
|
||||||
|
|
||||||
|
if( stat(path.c_str(), &sb ) == 0 )
|
||||||
|
return true;
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
realpath(const string& path)
|
||||||
|
{
|
||||||
|
char* real_path = realpath(path.c_str(), NULL);
|
||||||
|
|
||||||
|
string result;
|
||||||
|
|
||||||
|
if(real_path != NULL)
|
||||||
|
{
|
||||||
|
result = real_path;
|
||||||
|
|
||||||
|
free(real_path);
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
usb_sysfs_friendly_name(const string& sys_usb_path)
|
||||||
|
{
|
||||||
|
unsigned int device_number = 0;
|
||||||
|
|
||||||
|
istringstream( read_line(sys_usb_path + "/devnum") ) >> device_number;
|
||||||
|
|
||||||
|
string manufacturer = read_line( sys_usb_path + "/manufacturer" );
|
||||||
|
|
||||||
|
string product = read_line( sys_usb_path + "/product" );
|
||||||
|
|
||||||
|
string serial = read_line( sys_usb_path + "/serial" );
|
||||||
|
|
||||||
|
if( manufacturer.empty() && product.empty() && serial.empty() )
|
||||||
|
return "";
|
||||||
|
|
||||||
|
return format("%s %s %s", manufacturer.c_str(), product.c_str(), serial.c_str() );
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string>
|
||||||
|
get_sysfs_info(const string& device_path)
|
||||||
|
{
|
||||||
|
string device_name = basename( device_path );
|
||||||
|
|
||||||
|
string friendly_name;
|
||||||
|
|
||||||
|
string hardware_id;
|
||||||
|
|
||||||
|
string sys_device_path = format( "/sys/class/tty/%s/device", device_name.c_str() );
|
||||||
|
|
||||||
|
if( device_name.compare(0,6,"ttyUSB") == 0 )
|
||||||
|
{
|
||||||
|
sys_device_path = dirname( dirname( realpath( sys_device_path ) ) );
|
||||||
|
|
||||||
|
if( path_exists( sys_device_path ) )
|
||||||
|
{
|
||||||
|
friendly_name = usb_sysfs_friendly_name( sys_device_path );
|
||||||
|
|
||||||
|
hardware_id = usb_sysfs_hw_string( sys_device_path );
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if( device_name.compare(0,6,"ttyACM") == 0 )
|
||||||
|
{
|
||||||
|
sys_device_path = dirname( realpath( sys_device_path ) );
|
||||||
|
|
||||||
|
if( path_exists( sys_device_path ) )
|
||||||
|
{
|
||||||
|
friendly_name = usb_sysfs_friendly_name( sys_device_path );
|
||||||
|
|
||||||
|
hardware_id = usb_sysfs_hw_string( sys_device_path );
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// Try to read ID string of PCI device
|
||||||
|
|
||||||
|
string sys_id_path = sys_device_path + "/id";
|
||||||
|
|
||||||
|
if( path_exists( sys_id_path ) )
|
||||||
|
hardware_id = read_line( sys_id_path );
|
||||||
|
}
|
||||||
|
|
||||||
|
if( friendly_name.empty() )
|
||||||
|
friendly_name = device_name;
|
||||||
|
|
||||||
|
if( hardware_id.empty() )
|
||||||
|
hardware_id = "n/a";
|
||||||
|
|
||||||
|
vector<string> result;
|
||||||
|
result.push_back(friendly_name);
|
||||||
|
result.push_back(hardware_id);
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
read_line(const string& file)
|
||||||
|
{
|
||||||
|
ifstream ifs(file.c_str(), ifstream::in);
|
||||||
|
|
||||||
|
string line;
|
||||||
|
|
||||||
|
if(ifs)
|
||||||
|
{
|
||||||
|
getline(ifs, line);
|
||||||
|
}
|
||||||
|
|
||||||
|
return line;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
format(const char* format, ...)
|
||||||
|
{
|
||||||
|
va_list ap;
|
||||||
|
|
||||||
|
size_t buffer_size_bytes = 256;
|
||||||
|
|
||||||
|
string result;
|
||||||
|
|
||||||
|
char* buffer = (char*)malloc(buffer_size_bytes);
|
||||||
|
|
||||||
|
if( buffer == NULL )
|
||||||
|
return result;
|
||||||
|
|
||||||
|
bool done = false;
|
||||||
|
|
||||||
|
unsigned int loop_count = 0;
|
||||||
|
|
||||||
|
while(!done)
|
||||||
|
{
|
||||||
|
va_start(ap, format);
|
||||||
|
|
||||||
|
int return_value = vsnprintf(buffer, buffer_size_bytes, format, ap);
|
||||||
|
|
||||||
|
if( return_value < 0 )
|
||||||
|
{
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
else if( return_value >= buffer_size_bytes )
|
||||||
|
{
|
||||||
|
// Realloc and try again.
|
||||||
|
|
||||||
|
buffer_size_bytes = return_value + 1;
|
||||||
|
|
||||||
|
char* new_buffer_ptr = (char*)realloc(buffer, buffer_size_bytes);
|
||||||
|
|
||||||
|
if( new_buffer_ptr == NULL )
|
||||||
|
{
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
buffer = new_buffer_ptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
result = buffer;
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
va_end(ap);
|
||||||
|
|
||||||
|
if( ++loop_count > 5 )
|
||||||
|
done = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
free(buffer);
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
usb_sysfs_hw_string(const string& sysfs_path)
|
||||||
|
{
|
||||||
|
string serial_number = read_line( sysfs_path + "/serial" );
|
||||||
|
|
||||||
|
if( serial_number.length() > 0 )
|
||||||
|
{
|
||||||
|
serial_number = format( "SNR=%s", serial_number.c_str() );
|
||||||
|
}
|
||||||
|
|
||||||
|
string vid = read_line( sysfs_path + "/idVendor" );
|
||||||
|
|
||||||
|
string pid = read_line( sysfs_path + "/idProduct" );
|
||||||
|
|
||||||
|
return format("USB VID:PID=%s:%s %s", vid.c_str(), pid.c_str(), serial_number.c_str() );
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<PortInfo>
|
||||||
|
serial::list_ports()
|
||||||
|
{
|
||||||
|
vector<PortInfo> results;
|
||||||
|
|
||||||
|
vector<string> search_globs;
|
||||||
|
search_globs.push_back("/dev/ttyACM*");
|
||||||
|
search_globs.push_back("/dev/ttyS*");
|
||||||
|
search_globs.push_back("/dev/ttyUSB*");
|
||||||
|
search_globs.push_back("/dev/tty.*");
|
||||||
|
search_globs.push_back("/dev/cu.*");
|
||||||
|
|
||||||
|
vector<string> devices_found = glob( search_globs );
|
||||||
|
|
||||||
|
vector<string>::iterator iter = devices_found.begin();
|
||||||
|
|
||||||
|
while( iter != devices_found.end() )
|
||||||
|
{
|
||||||
|
string device = *iter++;
|
||||||
|
|
||||||
|
vector<string> sysfs_info = get_sysfs_info( device );
|
||||||
|
|
||||||
|
string friendly_name = sysfs_info[0];
|
||||||
|
|
||||||
|
string hardware_id = sysfs_info[1];
|
||||||
|
|
||||||
|
PortInfo device_entry;
|
||||||
|
device_entry.port = device;
|
||||||
|
device_entry.description = friendly_name;
|
||||||
|
device_entry.hardware_id = hardware_id;
|
||||||
|
|
||||||
|
results.push_back( device_entry );
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // defined(__linux__)
|
||||||
286
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_osx.cc
vendored
Normal file
286
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_osx.cc
vendored
Normal file
@@ -0,0 +1,286 @@
|
|||||||
|
#if defined(__APPLE__)
|
||||||
|
|
||||||
|
#include <sys/param.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <CoreFoundation/CoreFoundation.h>
|
||||||
|
#include <IOKit/IOKitLib.h>
|
||||||
|
#include <IOKit/serial/IOSerialKeys.h>
|
||||||
|
#include <IOKit/IOBSD.h>
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
using serial::PortInfo;
|
||||||
|
using std::string;
|
||||||
|
using std::vector;
|
||||||
|
|
||||||
|
#define HARDWARE_ID_STRING_LENGTH 128
|
||||||
|
|
||||||
|
string cfstring_to_string( CFStringRef cfstring );
|
||||||
|
string get_device_path( io_object_t& serial_port );
|
||||||
|
string get_class_name( io_object_t& obj );
|
||||||
|
io_registry_entry_t get_parent_iousb_device( io_object_t& serial_port );
|
||||||
|
string get_string_property( io_object_t& device, const char* property );
|
||||||
|
uint16_t get_int_property( io_object_t& device, const char* property );
|
||||||
|
string rtrim(const string& str);
|
||||||
|
|
||||||
|
string
|
||||||
|
cfstring_to_string( CFStringRef cfstring )
|
||||||
|
{
|
||||||
|
char cstring[MAXPATHLEN];
|
||||||
|
string result;
|
||||||
|
|
||||||
|
if( cfstring )
|
||||||
|
{
|
||||||
|
Boolean success = CFStringGetCString( cfstring,
|
||||||
|
cstring,
|
||||||
|
sizeof(cstring),
|
||||||
|
kCFStringEncodingASCII );
|
||||||
|
|
||||||
|
if( success )
|
||||||
|
result = cstring;
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
get_device_path( io_object_t& serial_port )
|
||||||
|
{
|
||||||
|
CFTypeRef callout_path;
|
||||||
|
string device_path;
|
||||||
|
|
||||||
|
callout_path = IORegistryEntryCreateCFProperty( serial_port,
|
||||||
|
CFSTR(kIOCalloutDeviceKey),
|
||||||
|
kCFAllocatorDefault,
|
||||||
|
0 );
|
||||||
|
|
||||||
|
if (callout_path)
|
||||||
|
{
|
||||||
|
if( CFGetTypeID(callout_path) == CFStringGetTypeID() )
|
||||||
|
device_path = cfstring_to_string( static_cast<CFStringRef>(callout_path) );
|
||||||
|
|
||||||
|
CFRelease(callout_path);
|
||||||
|
}
|
||||||
|
|
||||||
|
return device_path;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
get_class_name( io_object_t& obj )
|
||||||
|
{
|
||||||
|
string result;
|
||||||
|
io_name_t class_name;
|
||||||
|
kern_return_t kern_result;
|
||||||
|
|
||||||
|
kern_result = IOObjectGetClass( obj, class_name );
|
||||||
|
|
||||||
|
if( kern_result == KERN_SUCCESS )
|
||||||
|
result = class_name;
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
io_registry_entry_t
|
||||||
|
get_parent_iousb_device( io_object_t& serial_port )
|
||||||
|
{
|
||||||
|
io_object_t device = serial_port;
|
||||||
|
io_registry_entry_t parent = 0;
|
||||||
|
io_registry_entry_t result = 0;
|
||||||
|
kern_return_t kern_result = KERN_FAILURE;
|
||||||
|
string name = get_class_name(device);
|
||||||
|
|
||||||
|
// Walk the IO Registry tree looking for this devices parent IOUSBDevice.
|
||||||
|
while( name != "IOUSBDevice" )
|
||||||
|
{
|
||||||
|
kern_result = IORegistryEntryGetParentEntry( device,
|
||||||
|
kIOServicePlane,
|
||||||
|
&parent );
|
||||||
|
|
||||||
|
if(kern_result != KERN_SUCCESS)
|
||||||
|
{
|
||||||
|
result = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
device = parent;
|
||||||
|
|
||||||
|
name = get_class_name(device);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(kern_result == KERN_SUCCESS)
|
||||||
|
result = device;
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
get_string_property( io_object_t& device, const char* property )
|
||||||
|
{
|
||||||
|
string property_name;
|
||||||
|
|
||||||
|
if( device )
|
||||||
|
{
|
||||||
|
CFStringRef property_as_cfstring = CFStringCreateWithCString (
|
||||||
|
kCFAllocatorDefault,
|
||||||
|
property,
|
||||||
|
kCFStringEncodingASCII );
|
||||||
|
|
||||||
|
CFTypeRef name_as_cfstring = IORegistryEntryCreateCFProperty(
|
||||||
|
device,
|
||||||
|
property_as_cfstring,
|
||||||
|
kCFAllocatorDefault,
|
||||||
|
0 );
|
||||||
|
|
||||||
|
if( name_as_cfstring )
|
||||||
|
{
|
||||||
|
if( CFGetTypeID(name_as_cfstring) == CFStringGetTypeID() )
|
||||||
|
property_name = cfstring_to_string( static_cast<CFStringRef>(name_as_cfstring) );
|
||||||
|
|
||||||
|
CFRelease(name_as_cfstring);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(property_as_cfstring)
|
||||||
|
CFRelease(property_as_cfstring);
|
||||||
|
}
|
||||||
|
|
||||||
|
return property_name;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t
|
||||||
|
get_int_property( io_object_t& device, const char* property )
|
||||||
|
{
|
||||||
|
uint16_t result = 0;
|
||||||
|
|
||||||
|
if( device )
|
||||||
|
{
|
||||||
|
CFStringRef property_as_cfstring = CFStringCreateWithCString (
|
||||||
|
kCFAllocatorDefault,
|
||||||
|
property,
|
||||||
|
kCFStringEncodingASCII );
|
||||||
|
|
||||||
|
CFTypeRef number = IORegistryEntryCreateCFProperty( device,
|
||||||
|
property_as_cfstring,
|
||||||
|
kCFAllocatorDefault,
|
||||||
|
0 );
|
||||||
|
|
||||||
|
if(property_as_cfstring)
|
||||||
|
CFRelease(property_as_cfstring);
|
||||||
|
|
||||||
|
if( number )
|
||||||
|
{
|
||||||
|
if( CFGetTypeID(number) == CFNumberGetTypeID() )
|
||||||
|
{
|
||||||
|
bool success = CFNumberGetValue( static_cast<CFNumberRef>(number),
|
||||||
|
kCFNumberSInt16Type,
|
||||||
|
&result );
|
||||||
|
|
||||||
|
if( !success )
|
||||||
|
result = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
CFRelease(number);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
string rtrim(const string& str)
|
||||||
|
{
|
||||||
|
string result = str;
|
||||||
|
|
||||||
|
string whitespace = " \t\f\v\n\r";
|
||||||
|
|
||||||
|
std::size_t found = result.find_last_not_of(whitespace);
|
||||||
|
|
||||||
|
if (found != std::string::npos)
|
||||||
|
result.erase(found+1);
|
||||||
|
else
|
||||||
|
result.clear();
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<PortInfo>
|
||||||
|
serial::list_ports(void)
|
||||||
|
{
|
||||||
|
vector<PortInfo> devices_found;
|
||||||
|
CFMutableDictionaryRef classes_to_match;
|
||||||
|
io_iterator_t serial_port_iterator;
|
||||||
|
io_object_t serial_port;
|
||||||
|
mach_port_t master_port;
|
||||||
|
kern_return_t kern_result;
|
||||||
|
|
||||||
|
kern_result = IOMasterPort(MACH_PORT_NULL, &master_port);
|
||||||
|
|
||||||
|
if(kern_result != KERN_SUCCESS)
|
||||||
|
return devices_found;
|
||||||
|
|
||||||
|
classes_to_match = IOServiceMatching(kIOSerialBSDServiceValue);
|
||||||
|
|
||||||
|
if (classes_to_match == NULL)
|
||||||
|
return devices_found;
|
||||||
|
|
||||||
|
CFDictionarySetValue( classes_to_match,
|
||||||
|
CFSTR(kIOSerialBSDTypeKey),
|
||||||
|
CFSTR(kIOSerialBSDAllTypes) );
|
||||||
|
|
||||||
|
kern_result = IOServiceGetMatchingServices(master_port, classes_to_match, &serial_port_iterator);
|
||||||
|
|
||||||
|
if (KERN_SUCCESS != kern_result)
|
||||||
|
return devices_found;
|
||||||
|
|
||||||
|
while ( (serial_port = IOIteratorNext(serial_port_iterator)) )
|
||||||
|
{
|
||||||
|
string device_path = get_device_path( serial_port );
|
||||||
|
io_registry_entry_t parent = get_parent_iousb_device( serial_port );
|
||||||
|
IOObjectRelease(serial_port);
|
||||||
|
|
||||||
|
if( device_path.empty() )
|
||||||
|
continue;
|
||||||
|
|
||||||
|
PortInfo port_info;
|
||||||
|
port_info.port = device_path;
|
||||||
|
port_info.description = "n/a";
|
||||||
|
port_info.hardware_id = "n/a";
|
||||||
|
|
||||||
|
string device_name = rtrim( get_string_property( parent, "USB Product Name" ) );
|
||||||
|
string vendor_name = rtrim( get_string_property( parent, "USB Vendor Name") );
|
||||||
|
string description = rtrim( vendor_name + " " + device_name );
|
||||||
|
if( !description.empty() )
|
||||||
|
port_info.description = description;
|
||||||
|
|
||||||
|
string serial_number = rtrim(get_string_property( parent, "USB Serial Number" ) );
|
||||||
|
uint16_t vendor_id = get_int_property( parent, "idVendor" );
|
||||||
|
uint16_t product_id = get_int_property( parent, "idProduct" );
|
||||||
|
|
||||||
|
if( vendor_id && product_id )
|
||||||
|
{
|
||||||
|
char cstring[HARDWARE_ID_STRING_LENGTH];
|
||||||
|
|
||||||
|
if(serial_number.empty())
|
||||||
|
serial_number = "None";
|
||||||
|
|
||||||
|
int ret = snprintf( cstring, HARDWARE_ID_STRING_LENGTH, "USB VID:PID=%04x:%04x SNR=%s",
|
||||||
|
vendor_id,
|
||||||
|
product_id,
|
||||||
|
serial_number.c_str() );
|
||||||
|
|
||||||
|
if( (ret >= 0) && (ret < HARDWARE_ID_STRING_LENGTH) )
|
||||||
|
port_info.hardware_id = cstring;
|
||||||
|
}
|
||||||
|
|
||||||
|
devices_found.push_back(port_info);
|
||||||
|
}
|
||||||
|
|
||||||
|
IOObjectRelease(serial_port_iterator);
|
||||||
|
return devices_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // defined(__APPLE__)
|
||||||
152
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_win.cc
vendored
Normal file
152
scout_base/src/scout_sdk/src/third_party/serial/src/impl/list_ports/list_ports_win.cc
vendored
Normal file
@@ -0,0 +1,152 @@
|
|||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Copyright (c) 2014 Craig Lilley <cralilley@gmail.com>
|
||||||
|
* This software is made available under the terms of the MIT licence.
|
||||||
|
* A copy of the licence can be obtained from:
|
||||||
|
* http://opensource.org/licenses/MIT
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
#include <tchar.h>
|
||||||
|
#include <windows.h>
|
||||||
|
#include <setupapi.h>
|
||||||
|
#include <initguid.h>
|
||||||
|
#include <devguid.h>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
using serial::PortInfo;
|
||||||
|
using std::vector;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
static const DWORD port_name_max_length = 256;
|
||||||
|
static const DWORD friendly_name_max_length = 256;
|
||||||
|
static const DWORD hardware_id_max_length = 256;
|
||||||
|
|
||||||
|
// Convert a wide Unicode string to an UTF8 string
|
||||||
|
std::string utf8_encode(const std::wstring &wstr)
|
||||||
|
{
|
||||||
|
int size_needed = WideCharToMultiByte(CP_UTF8, 0, &wstr[0], (int)wstr.size(), NULL, 0, NULL, NULL);
|
||||||
|
std::string strTo( size_needed, 0 );
|
||||||
|
WideCharToMultiByte (CP_UTF8, 0, &wstr[0], (int)wstr.size(), &strTo[0], size_needed, NULL, NULL);
|
||||||
|
return strTo;
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<PortInfo>
|
||||||
|
serial::list_ports()
|
||||||
|
{
|
||||||
|
vector<PortInfo> devices_found;
|
||||||
|
|
||||||
|
HDEVINFO device_info_set = SetupDiGetClassDevs(
|
||||||
|
(const GUID *) &GUID_DEVCLASS_PORTS,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
DIGCF_PRESENT);
|
||||||
|
|
||||||
|
unsigned int device_info_set_index = 0;
|
||||||
|
SP_DEVINFO_DATA device_info_data;
|
||||||
|
|
||||||
|
device_info_data.cbSize = sizeof(SP_DEVINFO_DATA);
|
||||||
|
|
||||||
|
while(SetupDiEnumDeviceInfo(device_info_set, device_info_set_index, &device_info_data))
|
||||||
|
{
|
||||||
|
device_info_set_index++;
|
||||||
|
|
||||||
|
// Get port name
|
||||||
|
|
||||||
|
HKEY hkey = SetupDiOpenDevRegKey(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
DICS_FLAG_GLOBAL,
|
||||||
|
0,
|
||||||
|
DIREG_DEV,
|
||||||
|
KEY_READ);
|
||||||
|
|
||||||
|
TCHAR port_name[port_name_max_length];
|
||||||
|
DWORD port_name_length = port_name_max_length;
|
||||||
|
|
||||||
|
LONG return_code = RegQueryValueEx(
|
||||||
|
hkey,
|
||||||
|
_T("PortName"),
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
(LPBYTE)port_name,
|
||||||
|
&port_name_length);
|
||||||
|
|
||||||
|
RegCloseKey(hkey);
|
||||||
|
|
||||||
|
if(return_code != EXIT_SUCCESS)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
if(port_name_length > 0 && port_name_length <= port_name_max_length)
|
||||||
|
port_name[port_name_length-1] = '\0';
|
||||||
|
else
|
||||||
|
port_name[0] = '\0';
|
||||||
|
|
||||||
|
// Ignore parallel ports
|
||||||
|
|
||||||
|
if(_tcsstr(port_name, _T("LPT")) != NULL)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
// Get port friendly name
|
||||||
|
|
||||||
|
TCHAR friendly_name[friendly_name_max_length];
|
||||||
|
DWORD friendly_name_actual_length = 0;
|
||||||
|
|
||||||
|
BOOL got_friendly_name = SetupDiGetDeviceRegistryProperty(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
SPDRP_FRIENDLYNAME,
|
||||||
|
NULL,
|
||||||
|
(PBYTE)friendly_name,
|
||||||
|
friendly_name_max_length,
|
||||||
|
&friendly_name_actual_length);
|
||||||
|
|
||||||
|
if(got_friendly_name == TRUE && friendly_name_actual_length > 0)
|
||||||
|
friendly_name[friendly_name_actual_length-1] = '\0';
|
||||||
|
else
|
||||||
|
friendly_name[0] = '\0';
|
||||||
|
|
||||||
|
// Get hardware ID
|
||||||
|
|
||||||
|
TCHAR hardware_id[hardware_id_max_length];
|
||||||
|
DWORD hardware_id_actual_length = 0;
|
||||||
|
|
||||||
|
BOOL got_hardware_id = SetupDiGetDeviceRegistryProperty(
|
||||||
|
device_info_set,
|
||||||
|
&device_info_data,
|
||||||
|
SPDRP_HARDWAREID,
|
||||||
|
NULL,
|
||||||
|
(PBYTE)hardware_id,
|
||||||
|
hardware_id_max_length,
|
||||||
|
&hardware_id_actual_length);
|
||||||
|
|
||||||
|
if(got_hardware_id == TRUE && hardware_id_actual_length > 0)
|
||||||
|
hardware_id[hardware_id_actual_length-1] = '\0';
|
||||||
|
else
|
||||||
|
hardware_id[0] = '\0';
|
||||||
|
|
||||||
|
#ifdef UNICODE
|
||||||
|
std::string portName = utf8_encode(port_name);
|
||||||
|
std::string friendlyName = utf8_encode(friendly_name);
|
||||||
|
std::string hardwareId = utf8_encode(hardware_id);
|
||||||
|
#else
|
||||||
|
std::string portName = port_name;
|
||||||
|
std::string friendlyName = friendly_name;
|
||||||
|
std::string hardwareId = hardware_id;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
PortInfo port_entry;
|
||||||
|
port_entry.port = portName;
|
||||||
|
port_entry.description = friendlyName;
|
||||||
|
port_entry.hardware_id = hardwareId;
|
||||||
|
|
||||||
|
devices_found.push_back(port_entry);
|
||||||
|
}
|
||||||
|
|
||||||
|
SetupDiDestroyDeviceInfoList(device_info_set);
|
||||||
|
|
||||||
|
return devices_found;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // #if defined(_WIN32)
|
||||||
1066
scout_base/src/scout_sdk/src/third_party/serial/src/impl/unix.cc
vendored
Executable file
1066
scout_base/src/scout_sdk/src/third_party/serial/src/impl/unix.cc
vendored
Executable file
File diff suppressed because it is too large
Load Diff
646
scout_base/src/scout_sdk/src/third_party/serial/src/impl/win.cc
vendored
Normal file
646
scout_base/src/scout_sdk/src/third_party/serial/src/impl/win.cc
vendored
Normal file
@@ -0,0 +1,646 @@
|
|||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
/* Copyright 2012 William Woodall and John Harrison */
|
||||||
|
|
||||||
|
#include <sstream>
|
||||||
|
|
||||||
|
#include "serial/impl/win.h"
|
||||||
|
|
||||||
|
using std::string;
|
||||||
|
using std::wstring;
|
||||||
|
using std::stringstream;
|
||||||
|
using std::invalid_argument;
|
||||||
|
using serial::Serial;
|
||||||
|
using serial::Timeout;
|
||||||
|
using serial::bytesize_t;
|
||||||
|
using serial::parity_t;
|
||||||
|
using serial::stopbits_t;
|
||||||
|
using serial::flowcontrol_t;
|
||||||
|
using serial::SerialException;
|
||||||
|
using serial::PortNotOpenedException;
|
||||||
|
using serial::IOException;
|
||||||
|
|
||||||
|
inline wstring
|
||||||
|
_prefix_port_if_needed(const wstring &input)
|
||||||
|
{
|
||||||
|
static wstring windows_com_port_prefix = L"\\\\.\\";
|
||||||
|
if (input.compare(windows_com_port_prefix) != 0)
|
||||||
|
{
|
||||||
|
return windows_com_port_prefix + input;
|
||||||
|
}
|
||||||
|
return input;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity, stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol)
|
||||||
|
: port_ (port.begin(), port.end()), fd_ (INVALID_HANDLE_VALUE), is_open_ (false),
|
||||||
|
baudrate_ (baudrate), parity_ (parity),
|
||||||
|
bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
|
||||||
|
{
|
||||||
|
if (port_.empty () == false)
|
||||||
|
open ();
|
||||||
|
read_mutex = CreateMutex(NULL, false, NULL);
|
||||||
|
write_mutex = CreateMutex(NULL, false, NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::SerialImpl::~SerialImpl ()
|
||||||
|
{
|
||||||
|
this->close();
|
||||||
|
CloseHandle(read_mutex);
|
||||||
|
CloseHandle(write_mutex);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::open ()
|
||||||
|
{
|
||||||
|
if (port_.empty ()) {
|
||||||
|
throw invalid_argument ("Empty port is invalid.");
|
||||||
|
}
|
||||||
|
if (is_open_ == true) {
|
||||||
|
throw SerialException ("Serial port already open.");
|
||||||
|
}
|
||||||
|
|
||||||
|
// See: https://github.com/wjwwood/serial/issues/84
|
||||||
|
wstring port_with_prefix = _prefix_port_if_needed(port_);
|
||||||
|
LPCWSTR lp_port = port_with_prefix.c_str();
|
||||||
|
fd_ = CreateFileW(lp_port,
|
||||||
|
GENERIC_READ | GENERIC_WRITE,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
OPEN_EXISTING,
|
||||||
|
FILE_ATTRIBUTE_NORMAL,
|
||||||
|
0);
|
||||||
|
|
||||||
|
if (fd_ == INVALID_HANDLE_VALUE) {
|
||||||
|
DWORD create_file_err = GetLastError();
|
||||||
|
stringstream ss;
|
||||||
|
switch (create_file_err) {
|
||||||
|
case ERROR_FILE_NOT_FOUND:
|
||||||
|
// Use this->getPort to convert to a std::string
|
||||||
|
ss << "Specified port, " << this->getPort() << ", does not exist.";
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
default:
|
||||||
|
ss << "Unknown error opening the serial port: " << create_file_err;
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
reconfigurePort();
|
||||||
|
is_open_ = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::reconfigurePort ()
|
||||||
|
{
|
||||||
|
if (fd_ == INVALID_HANDLE_VALUE) {
|
||||||
|
// Can only operate on a valid file descriptor
|
||||||
|
THROW (IOException, "Invalid file descriptor, is the serial port open?");
|
||||||
|
}
|
||||||
|
|
||||||
|
DCB dcbSerialParams = {0};
|
||||||
|
|
||||||
|
dcbSerialParams.DCBlength=sizeof(dcbSerialParams);
|
||||||
|
|
||||||
|
if (!GetCommState(fd_, &dcbSerialParams)) {
|
||||||
|
//error getting state
|
||||||
|
THROW (IOException, "Error getting the serial port state.");
|
||||||
|
}
|
||||||
|
|
||||||
|
// setup baud rate
|
||||||
|
switch (baudrate_) {
|
||||||
|
#ifdef CBR_0
|
||||||
|
case 0: dcbSerialParams.BaudRate = CBR_0; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_50
|
||||||
|
case 50: dcbSerialParams.BaudRate = CBR_50; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_75
|
||||||
|
case 75: dcbSerialParams.BaudRate = CBR_75; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_110
|
||||||
|
case 110: dcbSerialParams.BaudRate = CBR_110; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_134
|
||||||
|
case 134: dcbSerialParams.BaudRate = CBR_134; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_150
|
||||||
|
case 150: dcbSerialParams.BaudRate = CBR_150; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_200
|
||||||
|
case 200: dcbSerialParams.BaudRate = CBR_200; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_300
|
||||||
|
case 300: dcbSerialParams.BaudRate = CBR_300; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_600
|
||||||
|
case 600: dcbSerialParams.BaudRate = CBR_600; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_1200
|
||||||
|
case 1200: dcbSerialParams.BaudRate = CBR_1200; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_1800
|
||||||
|
case 1800: dcbSerialParams.BaudRate = CBR_1800; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_2400
|
||||||
|
case 2400: dcbSerialParams.BaudRate = CBR_2400; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_4800
|
||||||
|
case 4800: dcbSerialParams.BaudRate = CBR_4800; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_7200
|
||||||
|
case 7200: dcbSerialParams.BaudRate = CBR_7200; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_9600
|
||||||
|
case 9600: dcbSerialParams.BaudRate = CBR_9600; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_14400
|
||||||
|
case 14400: dcbSerialParams.BaudRate = CBR_14400; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_19200
|
||||||
|
case 19200: dcbSerialParams.BaudRate = CBR_19200; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_28800
|
||||||
|
case 28800: dcbSerialParams.BaudRate = CBR_28800; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_57600
|
||||||
|
case 57600: dcbSerialParams.BaudRate = CBR_57600; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_76800
|
||||||
|
case 76800: dcbSerialParams.BaudRate = CBR_76800; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_38400
|
||||||
|
case 38400: dcbSerialParams.BaudRate = CBR_38400; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_115200
|
||||||
|
case 115200: dcbSerialParams.BaudRate = CBR_115200; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_128000
|
||||||
|
case 128000: dcbSerialParams.BaudRate = CBR_128000; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_153600
|
||||||
|
case 153600: dcbSerialParams.BaudRate = CBR_153600; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_230400
|
||||||
|
case 230400: dcbSerialParams.BaudRate = CBR_230400; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_256000
|
||||||
|
case 256000: dcbSerialParams.BaudRate = CBR_256000; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_460800
|
||||||
|
case 460800: dcbSerialParams.BaudRate = CBR_460800; break;
|
||||||
|
#endif
|
||||||
|
#ifdef CBR_921600
|
||||||
|
case 921600: dcbSerialParams.BaudRate = CBR_921600; break;
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
// Try to blindly assign it
|
||||||
|
dcbSerialParams.BaudRate = baudrate_;
|
||||||
|
}
|
||||||
|
|
||||||
|
// setup char len
|
||||||
|
if (bytesize_ == eightbits)
|
||||||
|
dcbSerialParams.ByteSize = 8;
|
||||||
|
else if (bytesize_ == sevenbits)
|
||||||
|
dcbSerialParams.ByteSize = 7;
|
||||||
|
else if (bytesize_ == sixbits)
|
||||||
|
dcbSerialParams.ByteSize = 6;
|
||||||
|
else if (bytesize_ == fivebits)
|
||||||
|
dcbSerialParams.ByteSize = 5;
|
||||||
|
else
|
||||||
|
throw invalid_argument ("invalid char len");
|
||||||
|
|
||||||
|
// setup stopbits
|
||||||
|
if (stopbits_ == stopbits_one)
|
||||||
|
dcbSerialParams.StopBits = ONESTOPBIT;
|
||||||
|
else if (stopbits_ == stopbits_one_point_five)
|
||||||
|
dcbSerialParams.StopBits = ONE5STOPBITS;
|
||||||
|
else if (stopbits_ == stopbits_two)
|
||||||
|
dcbSerialParams.StopBits = TWOSTOPBITS;
|
||||||
|
else
|
||||||
|
throw invalid_argument ("invalid stop bit");
|
||||||
|
|
||||||
|
// setup parity
|
||||||
|
if (parity_ == parity_none) {
|
||||||
|
dcbSerialParams.Parity = NOPARITY;
|
||||||
|
} else if (parity_ == parity_even) {
|
||||||
|
dcbSerialParams.Parity = EVENPARITY;
|
||||||
|
} else if (parity_ == parity_odd) {
|
||||||
|
dcbSerialParams.Parity = ODDPARITY;
|
||||||
|
} else if (parity_ == parity_mark) {
|
||||||
|
dcbSerialParams.Parity = MARKPARITY;
|
||||||
|
} else if (parity_ == parity_space) {
|
||||||
|
dcbSerialParams.Parity = SPACEPARITY;
|
||||||
|
} else {
|
||||||
|
throw invalid_argument ("invalid parity");
|
||||||
|
}
|
||||||
|
|
||||||
|
// setup flowcontrol
|
||||||
|
if (flowcontrol_ == flowcontrol_none) {
|
||||||
|
dcbSerialParams.fOutxCtsFlow = false;
|
||||||
|
dcbSerialParams.fRtsControl = RTS_CONTROL_DISABLE;
|
||||||
|
dcbSerialParams.fOutX = false;
|
||||||
|
dcbSerialParams.fInX = false;
|
||||||
|
}
|
||||||
|
if (flowcontrol_ == flowcontrol_software) {
|
||||||
|
dcbSerialParams.fOutxCtsFlow = false;
|
||||||
|
dcbSerialParams.fRtsControl = RTS_CONTROL_DISABLE;
|
||||||
|
dcbSerialParams.fOutX = true;
|
||||||
|
dcbSerialParams.fInX = true;
|
||||||
|
}
|
||||||
|
if (flowcontrol_ == flowcontrol_hardware) {
|
||||||
|
dcbSerialParams.fOutxCtsFlow = true;
|
||||||
|
dcbSerialParams.fRtsControl = RTS_CONTROL_HANDSHAKE;
|
||||||
|
dcbSerialParams.fOutX = false;
|
||||||
|
dcbSerialParams.fInX = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// activate settings
|
||||||
|
if (!SetCommState(fd_, &dcbSerialParams)){
|
||||||
|
CloseHandle(fd_);
|
||||||
|
THROW (IOException, "Error setting serial port settings.");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Setup timeouts
|
||||||
|
COMMTIMEOUTS timeouts = {0};
|
||||||
|
timeouts.ReadIntervalTimeout = timeout_.inter_byte_timeout;
|
||||||
|
timeouts.ReadTotalTimeoutConstant = timeout_.read_timeout_constant;
|
||||||
|
timeouts.ReadTotalTimeoutMultiplier = timeout_.read_timeout_multiplier;
|
||||||
|
timeouts.WriteTotalTimeoutConstant = timeout_.write_timeout_constant;
|
||||||
|
timeouts.WriteTotalTimeoutMultiplier = timeout_.write_timeout_multiplier;
|
||||||
|
if (!SetCommTimeouts(fd_, &timeouts)) {
|
||||||
|
THROW (IOException, "Error setting timeouts.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::close ()
|
||||||
|
{
|
||||||
|
if (is_open_ == true) {
|
||||||
|
if (fd_ != INVALID_HANDLE_VALUE) {
|
||||||
|
int ret;
|
||||||
|
ret = CloseHandle(fd_);
|
||||||
|
if (ret == 0) {
|
||||||
|
stringstream ss;
|
||||||
|
ss << "Error while closing serial port: " << GetLastError();
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
} else {
|
||||||
|
fd_ = INVALID_HANDLE_VALUE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
is_open_ = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::isOpen () const
|
||||||
|
{
|
||||||
|
return is_open_;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::SerialImpl::available ()
|
||||||
|
{
|
||||||
|
if (!is_open_) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
COMSTAT cs;
|
||||||
|
if (!ClearCommError(fd_, NULL, &cs)) {
|
||||||
|
stringstream ss;
|
||||||
|
ss << "Error while checking status of the serial port: " << GetLastError();
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
}
|
||||||
|
return static_cast<size_t>(cs.cbInQue);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::waitReadable (uint32_t /*timeout*/)
|
||||||
|
{
|
||||||
|
THROW (IOException, "waitReadable is not implemented on Windows.");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::waitByteTimes (size_t /*count*/)
|
||||||
|
{
|
||||||
|
THROW (IOException, "waitByteTimes is not implemented on Windows.");
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::SerialImpl::read (uint8_t *buf, size_t size)
|
||||||
|
{
|
||||||
|
if (!is_open_) {
|
||||||
|
throw PortNotOpenedException ("Serial::read");
|
||||||
|
}
|
||||||
|
DWORD bytes_read;
|
||||||
|
if (!ReadFile(fd_, buf, static_cast<DWORD>(size), &bytes_read, NULL)) {
|
||||||
|
stringstream ss;
|
||||||
|
ss << "Error while reading from the serial port: " << GetLastError();
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
}
|
||||||
|
return (size_t) (bytes_read);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::SerialImpl::write (const uint8_t *data, size_t length)
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::write");
|
||||||
|
}
|
||||||
|
DWORD bytes_written;
|
||||||
|
if (!WriteFile(fd_, data, static_cast<DWORD>(length), &bytes_written, NULL)) {
|
||||||
|
stringstream ss;
|
||||||
|
ss << "Error while writing to the serial port: " << GetLastError();
|
||||||
|
THROW (IOException, ss.str().c_str());
|
||||||
|
}
|
||||||
|
return (size_t) (bytes_written);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setPort (const string &port)
|
||||||
|
{
|
||||||
|
port_ = wstring(port.begin(), port.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
Serial::SerialImpl::getPort () const
|
||||||
|
{
|
||||||
|
return string(port_.begin(), port_.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setTimeout (serial::Timeout &timeout)
|
||||||
|
{
|
||||||
|
timeout_ = timeout;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::Timeout
|
||||||
|
Serial::SerialImpl::getTimeout () const
|
||||||
|
{
|
||||||
|
return timeout_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setBaudrate (unsigned long baudrate)
|
||||||
|
{
|
||||||
|
baudrate_ = baudrate;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long
|
||||||
|
Serial::SerialImpl::getBaudrate () const
|
||||||
|
{
|
||||||
|
return baudrate_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
|
||||||
|
{
|
||||||
|
bytesize_ = bytesize;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::bytesize_t
|
||||||
|
Serial::SerialImpl::getBytesize () const
|
||||||
|
{
|
||||||
|
return bytesize_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setParity (serial::parity_t parity)
|
||||||
|
{
|
||||||
|
parity_ = parity;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::parity_t
|
||||||
|
Serial::SerialImpl::getParity () const
|
||||||
|
{
|
||||||
|
return parity_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
|
||||||
|
{
|
||||||
|
stopbits_ = stopbits;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::stopbits_t
|
||||||
|
Serial::SerialImpl::getStopbits () const
|
||||||
|
{
|
||||||
|
return stopbits_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
|
||||||
|
{
|
||||||
|
flowcontrol_ = flowcontrol;
|
||||||
|
if (is_open_) {
|
||||||
|
reconfigurePort ();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::flowcontrol_t
|
||||||
|
Serial::SerialImpl::getFlowcontrol () const
|
||||||
|
{
|
||||||
|
return flowcontrol_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::flush ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::flush");
|
||||||
|
}
|
||||||
|
FlushFileBuffers (fd_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::flushInput ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException("Serial::flushInput");
|
||||||
|
}
|
||||||
|
PurgeComm(fd_, PURGE_RXCLEAR);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::flushOutput ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException("Serial::flushOutput");
|
||||||
|
}
|
||||||
|
PurgeComm(fd_, PURGE_TXCLEAR);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::sendBreak (int /*duration*/)
|
||||||
|
{
|
||||||
|
THROW (IOException, "sendBreak is not supported on Windows.");
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setBreak (bool level)
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::setBreak");
|
||||||
|
}
|
||||||
|
if (level) {
|
||||||
|
EscapeCommFunction (fd_, SETBREAK);
|
||||||
|
} else {
|
||||||
|
EscapeCommFunction (fd_, CLRBREAK);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setRTS (bool level)
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::setRTS");
|
||||||
|
}
|
||||||
|
if (level) {
|
||||||
|
EscapeCommFunction (fd_, SETRTS);
|
||||||
|
} else {
|
||||||
|
EscapeCommFunction (fd_, CLRRTS);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setDTR (bool level)
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::setDTR");
|
||||||
|
}
|
||||||
|
if (level) {
|
||||||
|
EscapeCommFunction (fd_, SETDTR);
|
||||||
|
} else {
|
||||||
|
EscapeCommFunction (fd_, CLRDTR);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::waitForChange ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::waitForChange");
|
||||||
|
}
|
||||||
|
DWORD dwCommEvent;
|
||||||
|
|
||||||
|
if (!SetCommMask(fd_, EV_CTS | EV_DSR | EV_RING | EV_RLSD)) {
|
||||||
|
// Error setting communications mask
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!WaitCommEvent(fd_, &dwCommEvent, NULL)) {
|
||||||
|
// An error occurred waiting for the event.
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
// Event has occurred.
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::getCTS ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::getCTS");
|
||||||
|
}
|
||||||
|
DWORD dwModemStatus;
|
||||||
|
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
|
||||||
|
THROW (IOException, "Error getting the status of the CTS line.");
|
||||||
|
}
|
||||||
|
|
||||||
|
return (MS_CTS_ON & dwModemStatus) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::getDSR ()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::getDSR");
|
||||||
|
}
|
||||||
|
DWORD dwModemStatus;
|
||||||
|
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
|
||||||
|
THROW (IOException, "Error getting the status of the DSR line.");
|
||||||
|
}
|
||||||
|
|
||||||
|
return (MS_DSR_ON & dwModemStatus) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::getRI()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::getRI");
|
||||||
|
}
|
||||||
|
DWORD dwModemStatus;
|
||||||
|
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
|
||||||
|
THROW (IOException, "Error getting the status of the RI line.");
|
||||||
|
}
|
||||||
|
|
||||||
|
return (MS_RING_ON & dwModemStatus) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::SerialImpl::getCD()
|
||||||
|
{
|
||||||
|
if (is_open_ == false) {
|
||||||
|
throw PortNotOpenedException ("Serial::getCD");
|
||||||
|
}
|
||||||
|
DWORD dwModemStatus;
|
||||||
|
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
|
||||||
|
// Error in GetCommModemStatus;
|
||||||
|
THROW (IOException, "Error getting the status of the CD line.");
|
||||||
|
}
|
||||||
|
|
||||||
|
return (MS_RLSD_ON & dwModemStatus) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::readLock()
|
||||||
|
{
|
||||||
|
if (WaitForSingleObject(read_mutex, INFINITE) != WAIT_OBJECT_0) {
|
||||||
|
THROW (IOException, "Error claiming read mutex.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::readUnlock()
|
||||||
|
{
|
||||||
|
if (!ReleaseMutex(read_mutex)) {
|
||||||
|
THROW (IOException, "Error releasing read mutex.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::writeLock()
|
||||||
|
{
|
||||||
|
if (WaitForSingleObject(write_mutex, INFINITE) != WAIT_OBJECT_0) {
|
||||||
|
THROW (IOException, "Error claiming write mutex.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::writeUnlock()
|
||||||
|
{
|
||||||
|
if (!ReleaseMutex(write_mutex)) {
|
||||||
|
THROW (IOException, "Error releasing write mutex.");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // #if defined(_WIN32)
|
||||||
|
|
||||||
430
scout_base/src/scout_sdk/src/third_party/serial/src/serial.cc
vendored
Executable file
430
scout_base/src/scout_sdk/src/third_party/serial/src/serial.cc
vendored
Executable file
@@ -0,0 +1,430 @@
|
|||||||
|
/* Copyright 2012 William Woodall and John Harrison */
|
||||||
|
#include <algorithm>
|
||||||
|
|
||||||
|
#if !defined(_WIN32) && !defined(__OpenBSD__) && !defined(__FreeBSD__)
|
||||||
|
# include <alloca.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined (__MINGW32__)
|
||||||
|
# define alloca __builtin_alloca
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include "serial/impl/win.h"
|
||||||
|
#else
|
||||||
|
#include "serial/impl/unix.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
using std::invalid_argument;
|
||||||
|
using std::min;
|
||||||
|
using std::numeric_limits;
|
||||||
|
using std::vector;
|
||||||
|
using std::size_t;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
using serial::Serial;
|
||||||
|
using serial::SerialException;
|
||||||
|
using serial::IOException;
|
||||||
|
using serial::bytesize_t;
|
||||||
|
using serial::parity_t;
|
||||||
|
using serial::stopbits_t;
|
||||||
|
using serial::flowcontrol_t;
|
||||||
|
|
||||||
|
class Serial::ScopedReadLock {
|
||||||
|
public:
|
||||||
|
ScopedReadLock(SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||||
|
this->pimpl_->readLock();
|
||||||
|
}
|
||||||
|
~ScopedReadLock() {
|
||||||
|
this->pimpl_->readUnlock();
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
ScopedReadLock(const ScopedReadLock&);
|
||||||
|
const ScopedReadLock& operator=(ScopedReadLock);
|
||||||
|
|
||||||
|
SerialImpl *pimpl_;
|
||||||
|
};
|
||||||
|
|
||||||
|
class Serial::ScopedWriteLock {
|
||||||
|
public:
|
||||||
|
ScopedWriteLock(SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||||
|
this->pimpl_->writeLock();
|
||||||
|
}
|
||||||
|
~ScopedWriteLock() {
|
||||||
|
this->pimpl_->writeUnlock();
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
// Disable copy constructors
|
||||||
|
ScopedWriteLock(const ScopedWriteLock&);
|
||||||
|
const ScopedWriteLock& operator=(ScopedWriteLock);
|
||||||
|
SerialImpl *pimpl_;
|
||||||
|
};
|
||||||
|
|
||||||
|
Serial::Serial (const string &port, uint32_t baudrate, serial::Timeout timeout,
|
||||||
|
bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol)
|
||||||
|
: pimpl_(new SerialImpl (port, baudrate, bytesize, parity,
|
||||||
|
stopbits, flowcontrol))
|
||||||
|
{
|
||||||
|
pimpl_->setTimeout(timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial::~Serial ()
|
||||||
|
{
|
||||||
|
delete pimpl_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::open ()
|
||||||
|
{
|
||||||
|
pimpl_->open ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::close ()
|
||||||
|
{
|
||||||
|
pimpl_->close ();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::isOpen () const
|
||||||
|
{
|
||||||
|
return pimpl_->isOpen ();
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::available ()
|
||||||
|
{
|
||||||
|
return pimpl_->available ();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
Serial::waitReadable ()
|
||||||
|
{
|
||||||
|
serial::Timeout timeout(pimpl_->getTimeout ());
|
||||||
|
return pimpl_->waitReadable(timeout.read_timeout_constant);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::waitByteTimes (size_t count)
|
||||||
|
{
|
||||||
|
pimpl_->waitByteTimes(count);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::read_ (uint8_t *buffer, size_t size)
|
||||||
|
{
|
||||||
|
return this->pimpl_->read (buffer, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::read (uint8_t *buffer, size_t size)
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
return this->pimpl_->read (buffer, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::read (std::vector<uint8_t> &buffer, size_t size)
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
uint8_t *buffer_ = new uint8_t[size];
|
||||||
|
size_t bytes_read = 0;
|
||||||
|
|
||||||
|
try {
|
||||||
|
bytes_read = this->pimpl_->read (buffer_, size);
|
||||||
|
}
|
||||||
|
catch (const std::exception &e) {
|
||||||
|
delete[] buffer_;
|
||||||
|
throw;
|
||||||
|
}
|
||||||
|
|
||||||
|
buffer.insert (buffer.end (), buffer_, buffer_+bytes_read);
|
||||||
|
delete[] buffer_;
|
||||||
|
return bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::read (std::string &buffer, size_t size)
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
uint8_t *buffer_ = new uint8_t[size];
|
||||||
|
size_t bytes_read = 0;
|
||||||
|
try {
|
||||||
|
bytes_read = this->pimpl_->read (buffer_, size);
|
||||||
|
}
|
||||||
|
catch (const std::exception &e) {
|
||||||
|
delete[] buffer_;
|
||||||
|
throw;
|
||||||
|
}
|
||||||
|
buffer.append (reinterpret_cast<const char*>(buffer_), bytes_read);
|
||||||
|
delete[] buffer_;
|
||||||
|
return bytes_read;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
Serial::read (size_t size)
|
||||||
|
{
|
||||||
|
std::string buffer;
|
||||||
|
this->read (buffer, size);
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::readline (string &buffer, size_t size, string eol)
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
size_t eol_len = eol.length ();
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t*>
|
||||||
|
(alloca (size * sizeof (uint8_t)));
|
||||||
|
size_t read_so_far = 0;
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
size_t bytes_read = this->read_ (buffer_ + read_so_far, 1);
|
||||||
|
read_so_far += bytes_read;
|
||||||
|
if (bytes_read == 0) {
|
||||||
|
break; // Timeout occured on reading 1 byte
|
||||||
|
}
|
||||||
|
if (string (reinterpret_cast<const char*>
|
||||||
|
(buffer_ + read_so_far - eol_len), eol_len) == eol) {
|
||||||
|
break; // EOL found
|
||||||
|
}
|
||||||
|
if (read_so_far == size) {
|
||||||
|
break; // Reached the maximum read length
|
||||||
|
}
|
||||||
|
}
|
||||||
|
buffer.append(reinterpret_cast<const char*> (buffer_), read_so_far);
|
||||||
|
return read_so_far;
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
Serial::readline (size_t size, string eol)
|
||||||
|
{
|
||||||
|
std::string buffer;
|
||||||
|
this->readline (buffer, size, eol);
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string>
|
||||||
|
Serial::readlines (size_t size, string eol)
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
std::vector<std::string> lines;
|
||||||
|
size_t eol_len = eol.length ();
|
||||||
|
uint8_t *buffer_ = static_cast<uint8_t*>
|
||||||
|
(alloca (size * sizeof (uint8_t)));
|
||||||
|
size_t read_so_far = 0;
|
||||||
|
size_t start_of_line = 0;
|
||||||
|
while (read_so_far < size) {
|
||||||
|
size_t bytes_read = this->read_ (buffer_+read_so_far, 1);
|
||||||
|
read_so_far += bytes_read;
|
||||||
|
if (bytes_read == 0) {
|
||||||
|
if (start_of_line != read_so_far) {
|
||||||
|
lines.push_back (
|
||||||
|
string (reinterpret_cast<const char*> (buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
}
|
||||||
|
break; // Timeout occured on reading 1 byte
|
||||||
|
}
|
||||||
|
if (string (reinterpret_cast<const char*>
|
||||||
|
(buffer_ + read_so_far - eol_len), eol_len) == eol) {
|
||||||
|
// EOL found
|
||||||
|
lines.push_back(
|
||||||
|
string(reinterpret_cast<const char*> (buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
start_of_line = read_so_far;
|
||||||
|
}
|
||||||
|
if (read_so_far == size) {
|
||||||
|
if (start_of_line != read_so_far) {
|
||||||
|
lines.push_back(
|
||||||
|
string(reinterpret_cast<const char*> (buffer_ + start_of_line),
|
||||||
|
read_so_far - start_of_line));
|
||||||
|
}
|
||||||
|
break; // Reached the maximum read length
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return lines;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::write (const string &data)
|
||||||
|
{
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_ (reinterpret_cast<const uint8_t*>(data.c_str()),
|
||||||
|
data.length());
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::write (const std::vector<uint8_t> &data)
|
||||||
|
{
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_ (&data[0], data.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::write (const uint8_t *data, size_t size)
|
||||||
|
{
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
return this->write_(data, size);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
Serial::write_ (const uint8_t *data, size_t length)
|
||||||
|
{
|
||||||
|
return pimpl_->write (data, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setPort (const string &port)
|
||||||
|
{
|
||||||
|
ScopedReadLock rlock(this->pimpl_);
|
||||||
|
ScopedWriteLock wlock(this->pimpl_);
|
||||||
|
bool was_open = pimpl_->isOpen ();
|
||||||
|
if (was_open) close();
|
||||||
|
pimpl_->setPort (port);
|
||||||
|
if (was_open) open ();
|
||||||
|
}
|
||||||
|
|
||||||
|
string
|
||||||
|
Serial::getPort () const
|
||||||
|
{
|
||||||
|
return pimpl_->getPort ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setTimeout (serial::Timeout &timeout)
|
||||||
|
{
|
||||||
|
pimpl_->setTimeout (timeout);
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::Timeout
|
||||||
|
Serial::getTimeout () const {
|
||||||
|
return pimpl_->getTimeout ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setBaudrate (uint32_t baudrate)
|
||||||
|
{
|
||||||
|
pimpl_->setBaudrate (baudrate);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t
|
||||||
|
Serial::getBaudrate () const
|
||||||
|
{
|
||||||
|
return uint32_t(pimpl_->getBaudrate ());
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setBytesize (bytesize_t bytesize)
|
||||||
|
{
|
||||||
|
pimpl_->setBytesize (bytesize);
|
||||||
|
}
|
||||||
|
|
||||||
|
bytesize_t
|
||||||
|
Serial::getBytesize () const
|
||||||
|
{
|
||||||
|
return pimpl_->getBytesize ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setParity (parity_t parity)
|
||||||
|
{
|
||||||
|
pimpl_->setParity (parity);
|
||||||
|
}
|
||||||
|
|
||||||
|
parity_t
|
||||||
|
Serial::getParity () const
|
||||||
|
{
|
||||||
|
return pimpl_->getParity ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setStopbits (stopbits_t stopbits)
|
||||||
|
{
|
||||||
|
pimpl_->setStopbits (stopbits);
|
||||||
|
}
|
||||||
|
|
||||||
|
stopbits_t
|
||||||
|
Serial::getStopbits () const
|
||||||
|
{
|
||||||
|
return pimpl_->getStopbits ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::setFlowcontrol (flowcontrol_t flowcontrol)
|
||||||
|
{
|
||||||
|
pimpl_->setFlowcontrol (flowcontrol);
|
||||||
|
}
|
||||||
|
|
||||||
|
flowcontrol_t
|
||||||
|
Serial::getFlowcontrol () const
|
||||||
|
{
|
||||||
|
return pimpl_->getFlowcontrol ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flush ()
|
||||||
|
{
|
||||||
|
ScopedReadLock rlock(this->pimpl_);
|
||||||
|
ScopedWriteLock wlock(this->pimpl_);
|
||||||
|
pimpl_->flush ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flushInput ()
|
||||||
|
{
|
||||||
|
ScopedReadLock lock(this->pimpl_);
|
||||||
|
pimpl_->flushInput ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::flushOutput ()
|
||||||
|
{
|
||||||
|
ScopedWriteLock lock(this->pimpl_);
|
||||||
|
pimpl_->flushOutput ();
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::sendBreak (int duration)
|
||||||
|
{
|
||||||
|
pimpl_->sendBreak (duration);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setBreak (bool level)
|
||||||
|
{
|
||||||
|
pimpl_->setBreak (level);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setRTS (bool level)
|
||||||
|
{
|
||||||
|
pimpl_->setRTS (level);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Serial::setDTR (bool level)
|
||||||
|
{
|
||||||
|
pimpl_->setDTR (level);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::waitForChange()
|
||||||
|
{
|
||||||
|
return pimpl_->waitForChange();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getCTS ()
|
||||||
|
{
|
||||||
|
return pimpl_->getCTS ();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getDSR ()
|
||||||
|
{
|
||||||
|
return pimpl_->getDSR ();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getRI ()
|
||||||
|
{
|
||||||
|
return pimpl_->getRI ();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool Serial::getCD ()
|
||||||
|
{
|
||||||
|
return pimpl_->getCD ();
|
||||||
|
}
|
||||||
12
scout_base/src/scout_sdk/src/third_party/serial/tests/CMakeLists.txt
vendored
Normal file
12
scout_base/src/scout_sdk/src/third_party/serial/tests/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
if(UNIX)
|
||||||
|
catkin_add_gtest(${PROJECT_NAME}-test unix_serial_tests.cc)
|
||||||
|
target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME} ${Boost_LIBRARIES})
|
||||||
|
if(NOT APPLE)
|
||||||
|
target_link_libraries(${PROJECT_NAME}-test util)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if(NOT APPLE) # these tests are unreliable on macOS
|
||||||
|
catkin_add_gtest(${PROJECT_NAME}-test-timer unit/unix_timer_tests.cc)
|
||||||
|
target_link_libraries(${PROJECT_NAME}-test-timer ${PROJECT_NAME})
|
||||||
|
endif()
|
||||||
|
endif()
|
||||||
1
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/mdc2250.cc
vendored
Normal file
1
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/mdc2250.cc
vendored
Normal file
@@ -0,0 +1 @@
|
|||||||
|
#include ""
|
||||||
15
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/python_serial_test.py
vendored
Normal file
15
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/python_serial_test.py
vendored
Normal file
@@ -0,0 +1,15 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
import serial, sys
|
||||||
|
|
||||||
|
if len(sys.argv) != 2:
|
||||||
|
print "python: Usage_serial_test <port name like: /dev/ttyUSB0>"
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
sio = serial.Serial(sys.argv[1], 115200)
|
||||||
|
sio.timeout = 250
|
||||||
|
|
||||||
|
while True:
|
||||||
|
sio.write("Testing.")
|
||||||
|
print sio.read(8)
|
||||||
|
|
||||||
31
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/tokenizer.cc
vendored
Normal file
31
scout_base/src/scout_sdk/src/third_party/serial/tests/proof_of_concepts/tokenizer.cc
vendored
Normal file
@@ -0,0 +1,31 @@
|
|||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include <boost/bind.hpp>
|
||||||
|
#include <boost/function.hpp>
|
||||||
|
#include <boost/algorithm/string.hpp>
|
||||||
|
#include <boost/foreach.hpp>
|
||||||
|
|
||||||
|
void
|
||||||
|
_delimeter_tokenizer (std::string &data, std::vector<std::string> &tokens,
|
||||||
|
std::string delimeter)
|
||||||
|
{
|
||||||
|
boost::split(tokens, data, boost::is_any_of(delimeter));
|
||||||
|
}
|
||||||
|
|
||||||
|
typedef boost::function<void(std::string&,std::vector<std::string>&)> TokenizerType;
|
||||||
|
|
||||||
|
int main(void) {
|
||||||
|
std::string data = "a\rb\rc\r";
|
||||||
|
std::vector<std::string> tokens;
|
||||||
|
std::string delimeter = "\r";
|
||||||
|
|
||||||
|
TokenizerType f = boost::bind(_delimeter_tokenizer, _1, _2, delimeter);
|
||||||
|
f(data, tokens);
|
||||||
|
|
||||||
|
BOOST_FOREACH(std::string token, tokens)
|
||||||
|
std::cout << token << std::endl;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
63
scout_base/src/scout_sdk/src/third_party/serial/tests/unit/unix_timer_tests.cc
vendored
Normal file
63
scout_base/src/scout_sdk/src/third_party/serial/tests/unit/unix_timer_tests.cc
vendored
Normal file
@@ -0,0 +1,63 @@
|
|||||||
|
#include "gtest/gtest.h"
|
||||||
|
#include "serial/impl/unix.h"
|
||||||
|
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
using serial::MillisecondTimer;
|
||||||
|
|
||||||
|
namespace {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Do 100 trials of timing gaps between 0 and 19 milliseconds.
|
||||||
|
* Expect accuracy within one millisecond.
|
||||||
|
*/
|
||||||
|
TEST(timer_tests, short_intervals) {
|
||||||
|
for (int trial = 0; trial < 100; trial++)
|
||||||
|
{
|
||||||
|
uint32_t ms = rand() % 20;
|
||||||
|
MillisecondTimer mt(ms);
|
||||||
|
usleep(1000 * ms);
|
||||||
|
int32_t r = mt.remaining();
|
||||||
|
|
||||||
|
// 1ms slush, for the cost of calling usleep.
|
||||||
|
EXPECT_NEAR(r+1, 0, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(timer_tests, overlapping_long_intervals) {
|
||||||
|
MillisecondTimer* timers[10];
|
||||||
|
|
||||||
|
// Experimentally determined. Corresponds to the extra time taken by the loops,
|
||||||
|
// the big usleep, and the test infrastructure itself.
|
||||||
|
const int slush_factor = 14;
|
||||||
|
|
||||||
|
// Set up the timers to each time one second, 1ms apart.
|
||||||
|
for (int t = 0; t < 10; t++)
|
||||||
|
{
|
||||||
|
timers[t] = new MillisecondTimer(1000);
|
||||||
|
usleep(1000);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check in on them after 500ms.
|
||||||
|
usleep(500000);
|
||||||
|
for (int t = 0; t < 10; t++)
|
||||||
|
{
|
||||||
|
EXPECT_NEAR(timers[t]->remaining(), 500 - slush_factor + t, 5);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check in on them again after another 500ms and free them.
|
||||||
|
usleep(500000);
|
||||||
|
for (int t = 0; t < 10; t++)
|
||||||
|
{
|
||||||
|
EXPECT_NEAR(timers[t]->remaining(), -slush_factor + t, 5);
|
||||||
|
delete timers[t];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
int main(int argc, char **argv) {
|
||||||
|
::testing::InitGoogleTest(&argc, argv);
|
||||||
|
return RUN_ALL_TESTS();
|
||||||
|
}
|
||||||
118
scout_base/src/scout_sdk/src/third_party/serial/tests/unix_serial_tests.cc
vendored
Normal file
118
scout_base/src/scout_sdk/src/third_party/serial/tests/unix_serial_tests.cc
vendored
Normal file
@@ -0,0 +1,118 @@
|
|||||||
|
/* To run these tests you need to change the define below to the serial port
|
||||||
|
* with a loop back device attached.
|
||||||
|
*
|
||||||
|
* Alternatively you could use an Arduino:
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
Serial.begin(115200);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
while (Serial.available() > 0) {
|
||||||
|
Serial.write(Serial.read());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
|
#include <boost/bind.hpp>
|
||||||
|
|
||||||
|
// Use FRIEND_TEST... its not as nasty, thats what friends are for
|
||||||
|
// // OMG this is so nasty...
|
||||||
|
// #define private public
|
||||||
|
// #define protected public
|
||||||
|
|
||||||
|
#include "serial/serial.h"
|
||||||
|
|
||||||
|
#if defined(__linux__)
|
||||||
|
#include <pty.h>
|
||||||
|
#else
|
||||||
|
#include <util.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
using namespace serial;
|
||||||
|
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
namespace {
|
||||||
|
|
||||||
|
class SerialTests : public ::testing::Test {
|
||||||
|
protected:
|
||||||
|
virtual void SetUp() {
|
||||||
|
if (openpty(&master_fd, &slave_fd, name, NULL, NULL) == -1) {
|
||||||
|
perror("openpty");
|
||||||
|
exit(127);
|
||||||
|
}
|
||||||
|
|
||||||
|
ASSERT_TRUE(master_fd > 0);
|
||||||
|
ASSERT_TRUE(slave_fd > 0);
|
||||||
|
ASSERT_TRUE(string(name).length() > 0);
|
||||||
|
|
||||||
|
port1 = new Serial(string(name), 115200, Timeout::simpleTimeout(250));
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void TearDown() {
|
||||||
|
port1->close();
|
||||||
|
delete port1;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial * port1;
|
||||||
|
int master_fd;
|
||||||
|
int slave_fd;
|
||||||
|
char name[100];
|
||||||
|
};
|
||||||
|
|
||||||
|
TEST_F(SerialTests, readWorks) {
|
||||||
|
write(master_fd, "abc\n", 4);
|
||||||
|
string r = port1->read(4);
|
||||||
|
EXPECT_EQ(r, string("abc\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(SerialTests, writeWorks) {
|
||||||
|
char buf[5] = "";
|
||||||
|
port1->write("abc\n");
|
||||||
|
read(master_fd, buf, 4);
|
||||||
|
EXPECT_EQ(string(buf, 4), string("abc\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(SerialTests, timeoutWorks) {
|
||||||
|
// Timeout a read, returns an empty string
|
||||||
|
string empty = port1->read();
|
||||||
|
EXPECT_EQ(empty, string(""));
|
||||||
|
|
||||||
|
// Ensure that writing/reading still works after a timeout.
|
||||||
|
write(master_fd, "abc\n", 4);
|
||||||
|
string r = port1->read(4);
|
||||||
|
EXPECT_EQ(r, string("abc\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(SerialTests, partialRead) {
|
||||||
|
// Write some data, but request more than was written.
|
||||||
|
write(master_fd, "abc\n", 4);
|
||||||
|
|
||||||
|
// Should timeout, but return what was in the buffer.
|
||||||
|
string empty = port1->read(10);
|
||||||
|
EXPECT_EQ(empty, string("abc\n"));
|
||||||
|
|
||||||
|
// Ensure that writing/reading still works after a timeout.
|
||||||
|
write(master_fd, "abc\n", 4);
|
||||||
|
string r = port1->read(4);
|
||||||
|
EXPECT_EQ(r, string("abc\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
int main(int argc, char **argv) {
|
||||||
|
try {
|
||||||
|
::testing::InitGoogleTest(&argc, argv);
|
||||||
|
return RUN_ALL_TESTS();
|
||||||
|
} catch (std::exception &e) {
|
||||||
|
std::cerr << "Unhandled Exception: " << e.what() << std::endl;
|
||||||
|
}
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
8
scout_base/src/scout_sdk/src/third_party/stopwatch/CMakeLists.txt
vendored
Normal file
8
scout_base/src/scout_sdk/src/third_party/stopwatch/CMakeLists.txt
vendored
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
cmake_minimum_required(VERSION 3.0.0)
|
||||||
|
project(stopwatch)
|
||||||
|
|
||||||
|
# ascent library
|
||||||
|
add_library(stopwatch INTERFACE)
|
||||||
|
target_include_directories(stopwatch INTERFACE
|
||||||
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
|
$<INSTALL_INTERFACE:include>)
|
||||||
24
scout_base/src/scout_sdk/src/third_party/stopwatch/LICENSE
vendored
Normal file
24
scout_base/src/scout_sdk/src/third_party/stopwatch/LICENSE
vendored
Normal file
@@ -0,0 +1,24 @@
|
|||||||
|
This is free and unencumbered software released into the public domain.
|
||||||
|
|
||||||
|
Anyone is free to copy, modify, publish, use, compile, sell, or
|
||||||
|
distribute this software, either in source code form or as a compiled
|
||||||
|
binary, for any purpose, commercial or non-commercial, and by any
|
||||||
|
means.
|
||||||
|
|
||||||
|
In jurisdictions that recognize copyright laws, the author or authors
|
||||||
|
of this software dedicate any and all copyright interest in the
|
||||||
|
software to the public domain. We make this dedication for the benefit
|
||||||
|
of the public at large and to the detriment of our heirs and
|
||||||
|
successors. We intend this dedication to be an overt act of
|
||||||
|
relinquishment in perpetuity of all present and future rights to this
|
||||||
|
software under copyright law.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||||||
|
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
|
||||||
|
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
|
||||||
|
IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
|
||||||
|
OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
|
||||||
|
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
|
||||||
|
OTHER DEALINGS IN THE SOFTWARE.
|
||||||
|
|
||||||
|
For more information, please refer to <http://unlicense.org>
|
||||||
123
scout_base/src/scout_sdk/src/third_party/stopwatch/README.md
vendored
Normal file
123
scout_base/src/scout_sdk/src/third_party/stopwatch/README.md
vendored
Normal file
@@ -0,0 +1,123 @@
|
|||||||
|
# ⏱️ stopwatch
|
||||||
|
Single-header C++11 RDTSCP clock and timing utils released into the public domain.
|
||||||
|
|
||||||
|
# why
|
||||||
|
While developing games, I have wanted the following features which are not provided by `std::chrono`:
|
||||||
|
1. triggering events after a certain amount of time
|
||||||
|
2. timing function calls in a high precision manner
|
||||||
|
|
||||||
|
# requirements
|
||||||
|
1. The `RDTSCP` instruction and a compiler which supports C++11 or higher.
|
||||||
|
2. Your processor must have an [Intel Nehalem (2008)](https://en.wikipedia.org/wiki/Nehalem_(microarchitecture)) or newer processor _or_ a processeor with an invariant TSC.
|
||||||
|
|
||||||
|
If you do not meet these requirements, you can easily remove the `RDTSCP` code from the library and enjoy the other features. The relevant sections of the [The Intel Software Developer Manuals](http://www.intel.com/Assets/en_US/PDF/manual/253668.pdf) are at the bottom of this page.
|
||||||
|
|
||||||
|
# usage
|
||||||
|
## timer
|
||||||
|
```c++
|
||||||
|
#include "stopwatch.h"
|
||||||
|
#include <chrono>
|
||||||
|
#include <iostream>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
const auto timer = stopwatch::make_timer(std::chrono::seconds(10));
|
||||||
|
while (!timer.done()) {
|
||||||
|
std::cout << std::chrono::duration_cast<std::chrono::seconds>(
|
||||||
|
timer.remaining())
|
||||||
|
.count()
|
||||||
|
<< " seconds remain." << std::endl;
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(100));
|
||||||
|
}
|
||||||
|
std::cout << "10 seconds have elapsed" << std::endl;
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
## timing one function call
|
||||||
|
```c++
|
||||||
|
#include "stopwatch.h"
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
const auto cycles = stopwatch::time([] {
|
||||||
|
for (std::size_t i = 0; i < 10; ++i) {
|
||||||
|
std::cout << i << std::endl;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
std::cout << "To print out 10 numbers, it took " << cycles.count()
|
||||||
|
<< " cycles." << std::endl;
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
## sampling multiple calls to a function
|
||||||
|
Taking the median number of cycles for inserting 10000 items into the beginning of a container.
|
||||||
|
```c++
|
||||||
|
#include "stopwatch.h"
|
||||||
|
#include <deque>
|
||||||
|
#include <iostream>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
int main() {
|
||||||
|
const auto deque_samples = stopwatch::sample<100>([] {
|
||||||
|
std::deque<int> deque;
|
||||||
|
for (std::size_t i = 0; i < 10000; ++i) {
|
||||||
|
deque.insert(deque.begin(), i);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
const auto vector_samples = stopwatch::sample<100>([] {
|
||||||
|
std::vector<int> vector;
|
||||||
|
for (std::size_t i = 0; i < 10000; ++i) {
|
||||||
|
vector.insert(vector.begin(), i);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
std::cout << "median for deque: " << deque_samples[49].count() << std::endl;
|
||||||
|
std::cout << "median for vector: " << vector_samples[49].count() << std::endl;
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
Output on my MacbookPro 2016:
|
||||||
|
```
|
||||||
|
median for deque: 487760
|
||||||
|
median for vector: 7595754
|
||||||
|
```
|
||||||
|
|
||||||
|
# using another clock
|
||||||
|
Using another clock is as simple as passing the clock in as a template argument. An example using `std::chrono::system_clock` inplace of `stopwatch::rdtscp_clock` for the `timing one function call` example:
|
||||||
|
```c++
|
||||||
|
const auto cycles = stopwatch::time<std::chrono::system_clock>([] {
|
||||||
|
for (std::size_t i = 0; i < 10; ++i) {
|
||||||
|
std::cout << i << std::endl;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
```
|
||||||
|
`stopwatch::time([] { ... })` became `stopwatch::time<std::chrono::system_clock>([] { ... }`. That's it!
|
||||||
|
|
||||||
|
# contributing
|
||||||
|
Contributions of any variety are greatly appreciated. All code is passed through `clang-format` using the Google style.
|
||||||
|
|
||||||
|
## [The Intel Software Developer Manuals](http://www.intel.com/Assets/en_US/PDF/manual/253668.pdf)
|
||||||
|
### Section 16.12.1
|
||||||
|
> The time stamp counter in newer processors may support an enhancement, referred
|
||||||
|
to as invariant TSC. Processor’s support for invariant TSC is indicated by
|
||||||
|
CPUID.80000007H:EDX[8].
|
||||||
|
The invariant TSC will run at a constant rate in all ACPI P-, C-. and T-states. This is
|
||||||
|
the architectural behavior moving forward. On processors with invariant TSC
|
||||||
|
support, the OS may use the TSC for wall clock timer services (instead of ACPI or
|
||||||
|
HPET timers). TSC reads are much more efficient and do not incur the overhead
|
||||||
|
associated with a ring transition or access to a platform resource.
|
||||||
|
|
||||||
|
### Section 16.12.2
|
||||||
|
> Processors based on Intel microarchitecture code name Nehalem provide an auxiliary
|
||||||
|
TSC register, IA32_TSC_AUX that is designed to be used in conjunction with
|
||||||
|
IA32_TSC. IA32_TSC_AUX provides a 32-bit field that is initialized by privileged software
|
||||||
|
with a signature value (for example, a logical processor ID).
|
||||||
|
|
||||||
|
> The primary usage of IA32_TSC_AUX in conjunction with IA32_TSC is to allow software
|
||||||
|
to read the 64-bit time stamp in IA32_TSC and signature value in
|
||||||
|
IA32_TSC_AUX with the instruction RDTSCP in an atomic operation. RDTSCP returns
|
||||||
|
the 64-bit time stamp in EDX:EAX and the 32-bit TSC_AUX signature value in ECX.
|
||||||
|
The atomicity of RDTSCP ensures that no context switch can occur between the reads
|
||||||
|
of the TSC and TSC_AUX values.
|
||||||
146
scout_base/src/scout_sdk/src/third_party/stopwatch/include/stopwatch/stopwatch.h
vendored
Normal file
146
scout_base/src/scout_sdk/src/third_party/stopwatch/include/stopwatch/stopwatch.h
vendored
Normal file
@@ -0,0 +1,146 @@
|
|||||||
|
#ifndef STOPWATCH_H_
|
||||||
|
#define STOPWATCH_H_
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <array>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cstdint>
|
||||||
|
#include <ratio>
|
||||||
|
|
||||||
|
namespace stopwatch
|
||||||
|
{
|
||||||
|
// only supported on x86 processors
|
||||||
|
#if (defined __x86_64__) || (defined __i386)
|
||||||
|
// An implementation of the 'TrivialClock' concept using the rdtscp instruction.
|
||||||
|
struct rdtscp_clock
|
||||||
|
{
|
||||||
|
using rep = std::uint64_t;
|
||||||
|
using period = std::ratio<1>;
|
||||||
|
using duration = std::chrono::duration<rep, period>;
|
||||||
|
using time_point = std::chrono::time_point<rdtscp_clock, duration>;
|
||||||
|
|
||||||
|
static auto now() noexcept -> time_point
|
||||||
|
{
|
||||||
|
std::uint32_t hi, lo;
|
||||||
|
__asm__ __volatile__("rdtscp"
|
||||||
|
: "=d"(hi), "=a"(lo));
|
||||||
|
return time_point(duration((static_cast<std::uint64_t>(hi) << 32) | lo));
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// A timer using the specified clock.
|
||||||
|
template <class Clock = std::chrono::system_clock>
|
||||||
|
struct timer
|
||||||
|
{
|
||||||
|
using time_point = typename Clock::time_point;
|
||||||
|
using duration = typename Clock::duration;
|
||||||
|
|
||||||
|
timer(const duration duration) noexcept : expiry(Clock::now() + duration) {}
|
||||||
|
timer(const time_point expiry) noexcept : expiry(expiry) {}
|
||||||
|
|
||||||
|
bool done(time_point now = Clock::now()) const noexcept
|
||||||
|
{
|
||||||
|
return now >= expiry;
|
||||||
|
}
|
||||||
|
|
||||||
|
auto remaining(time_point now = Clock::now()) const noexcept -> duration
|
||||||
|
{
|
||||||
|
return expiry - now;
|
||||||
|
}
|
||||||
|
|
||||||
|
const time_point expiry;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <class Clock = std::chrono::system_clock>
|
||||||
|
constexpr auto make_timer(typename Clock::duration duration) -> timer<Clock>
|
||||||
|
{
|
||||||
|
return timer<Clock>(duration);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Times how long it takes a function to execute using the specified clock.
|
||||||
|
template <class Clock = rdtscp_clock, class Func>
|
||||||
|
auto time(Func &&function) -> typename Clock::duration
|
||||||
|
{
|
||||||
|
const auto start = Clock::now();
|
||||||
|
function();
|
||||||
|
return Clock::now() - start;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Samples the given function N times using the specified clock.
|
||||||
|
template <std::size_t N, class Clock = rdtscp_clock, class Func>
|
||||||
|
auto sample(Func &&function) -> std::array<typename Clock::duration, N>
|
||||||
|
{
|
||||||
|
std::array<typename Clock::duration, N> samples;
|
||||||
|
|
||||||
|
for (std::size_t i = 0u; i < N; ++i)
|
||||||
|
{
|
||||||
|
samples[i] = time<Clock>(function);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::sort(samples.begin(), samples.end());
|
||||||
|
return samples;
|
||||||
|
}
|
||||||
|
#endif /* __x86_64__ or __i386 */
|
||||||
|
|
||||||
|
struct StopWatch
|
||||||
|
{
|
||||||
|
using Clock = std::chrono::high_resolution_clock;
|
||||||
|
using time_point = typename Clock::time_point;
|
||||||
|
using duration = typename Clock::duration;
|
||||||
|
|
||||||
|
StopWatch() { tic_point = Clock::now(); };
|
||||||
|
|
||||||
|
time_point tic_point;
|
||||||
|
|
||||||
|
void tic()
|
||||||
|
{
|
||||||
|
tic_point = Clock::now();
|
||||||
|
};
|
||||||
|
|
||||||
|
double toc()
|
||||||
|
{
|
||||||
|
return std::chrono::duration_cast<std::chrono::microseconds>(Clock::now() - tic_point).count() / 1000000.0;
|
||||||
|
};
|
||||||
|
|
||||||
|
// for different precisions
|
||||||
|
double stoc()
|
||||||
|
{
|
||||||
|
return std::chrono::duration_cast<std::chrono::seconds>(Clock::now() - tic_point).count();
|
||||||
|
};
|
||||||
|
|
||||||
|
double mtoc()
|
||||||
|
{
|
||||||
|
return std::chrono::duration_cast<std::chrono::milliseconds>(Clock::now() - tic_point).count();
|
||||||
|
};
|
||||||
|
|
||||||
|
double utoc()
|
||||||
|
{
|
||||||
|
return std::chrono::duration_cast<std::chrono::microseconds>(Clock::now() - tic_point).count();
|
||||||
|
};
|
||||||
|
|
||||||
|
double ntoc()
|
||||||
|
{
|
||||||
|
return std::chrono::duration_cast<std::chrono::nanoseconds>(Clock::now() - tic_point).count();
|
||||||
|
};
|
||||||
|
|
||||||
|
// you have to call tic() before calling this function
|
||||||
|
void sleep_until_ms(int64_t period_ms)
|
||||||
|
{
|
||||||
|
int64_t duration = period_ms - std::chrono::duration_cast<std::chrono::milliseconds>(Clock::now() - tic_point).count();
|
||||||
|
|
||||||
|
if (duration > 0)
|
||||||
|
std::this_thread::sleep_for(std::chrono::milliseconds(duration));
|
||||||
|
};
|
||||||
|
|
||||||
|
void sleep_until_us(int64_t period_us)
|
||||||
|
{
|
||||||
|
int64_t duration = period_us - std::chrono::duration_cast<std::chrono::microseconds>(Clock::now() - tic_point).count();
|
||||||
|
|
||||||
|
if (duration > 0)
|
||||||
|
std::this_thread::sleep_for(std::chrono::microseconds(duration));
|
||||||
|
};
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace stopwatch
|
||||||
|
|
||||||
|
#endif // STOPWATCH_H_
|
||||||
Reference in New Issue
Block a user