...
 
Commits (9)
......@@ -2,8 +2,30 @@
Changelog for package rplidar_ros
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Forthcoming
-----------
1.9.0 (2018-08-24)
------------------
* Update RPLIDAR SDK to 1.9.0
* [new feature] support baudrate 57600 and 1382400, support HQ scan response
* [bugfix] TCP channel doesn't work
* [improvement] Print warning messages when deprecated APIs are called; imporve angular accuracy for ultra capsuled scan points
* Contributors: tony,kint
1.7.0 (2018-07-19)
------------------
* Update RPLIDAR SDK to 1.7.0
* support scan points farther than 16.38m
* upport display and set scan mode
* Contributors: kint
1.6.0 (2018-05-21)
------------------
* Release 1.6.0.
* Update RPLIDAR SDK to 1.6.0
* Support new product RPLIDAR A3(default 16K model and max_distance 25m)
* Contributors: kint
1.5.7 (2016-12-15)
------------------
* Release 1.5.7.
......
Copyright (c) 2009 - 2014 RoboPeak Team
Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
All rights reserved.
Redistribution and use in source and binary forms, with or without
......
......@@ -9,6 +9,8 @@ rplidar roswiki: http://wiki.ros.org/rplidar
rplidar HomePage: http://www.slamtec.com/en/Lidar
rplidar SDK: https://github.com/Slamtec/rplidar_sdk
rplidar Tutorial: https://github.com/robopeak/rplidar_ros/wiki
How to build rplidar ros package
......@@ -22,19 +24,24 @@ There're two ways to run rplidar ros package
I. Run rplidar node and view in the rviz
------------------------------------------------------------
roslaunch rplidar_ros view_rplidar.launch
roslaunch rplidar_ros view_rplidar.launch (for RPLIDAR A1/A2)
or
roslaunch rplidar_ros view_rplidar_a3.launch (for RPLIDAR A3)
You should see rplidar's scan result in the rviz.
II. Run rplidar node and view using test application
------------------------------------------------------------
roslaunch rplidar_ros rplidar.launch
roslaunch rplidar_ros rplidar.launch (for RPLIDAR A1/A2)
or
roslaunch rplidar_ros rplidar_a3.launch (for RPLIDAR A3)
rosrun rplidar_ros rplidarNodeClient
You should see rplidar's scan result in the console
Notice: the different is serial_baudrate between A1/A2 and A3
RPLidar frame
=====================================================================
RPLidar frame must be broadcasted according to picture shown in
rplidar-frame.png
RPLidar frame must be broadcasted according to picture shown in rplidar-frame.png
<launch>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB002"/>
<param name="serial_port" type="string" value="/dev/ttyUSB002"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
......
<launch>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB002"/>
<param name="serial_baudrate" type="int" value="256000"/><!--A3 -->
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<param name="scan_mode" type="string" value="Sensitivity"/>
</node>
</launch>
......@@ -5,7 +5,7 @@
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
<node name="rplidarNodeClient" pkg="rplidar_ros" type="rplidarNodeClient" output="screen">
</node>
......
<launch>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB002"/>
<param name="serial_baudrate" type="int" value="256000"/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
<param name="scan_mode" type="string" value="Sensitivity"/>
</node>
<node name="rplidarNodeClient" pkg="rplidar_ros" type="rplidarNodeClient" output="screen">
</node>
</launch>
<!--
Used for visualising rplidar in action.
It requires rplidar.launch.
-->
<launch>
<include file="$(find rplidar_ros)/launch/rplidar_a3.launch" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find rplidar_ros)/rviz/rplidar.rviz" />
</launch>
<?xml version="1.0"?>
<package>
<name>rplidar_ros</name>
<version>1.5.7</version>
<description>The rplidar ros package, support rplidar A2/A1 </description>
<version>1.9.0</version>
<description>The rplidar ros package, support rplidar A2/A1 and A3</description>
<maintainer email="ros@slamtec.com">Slamtec ROS Maintainer</maintainer>
<license>BSD</license>
......
Copyright (c) 2009 - 2014 RoboPeak Team
Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
All rights reserved.
Redistribution and use in source and binary forms, with or without
......@@ -29,6 +29,6 @@ This folder contains RPLIDAR SDK source code which is provided by RoboPeak.
RoboPeak Website: http://www.robopeak.com
SlamTec HomePage: http://www.slamtec.com
RPLIDAR_SDK_VERSION: 1.5.7
RPLIDAR_SDK_VERSION: 1.9.0
Note: The SDK version may not up-to-date.
rplidar product: http://www.slamtec.com/en/Lidar
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -34,10 +34,11 @@
#pragma once
#include "rptypes.h"
#include <vector>
#include "hal/types.h"
#include "rplidar_protocol.h"
#include "rplidar_cmd.h"
#include "rplidar_driver.h"
#define RPLIDAR_SDK_VERSION "1.5.7"
#define RPLIDAR_SDK_VERSION "1.9.0"
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -52,9 +52,13 @@
#define RPLIDAR_CMD_GET_SAMPLERATE 0x59 //added in fw 1.17
#define RPLIDAR_CMD_HQ_MOTOR_SPEED_CTRL 0xA8
// Commands with payload and have response
#define RPLIDAR_CMD_EXPRESS_SCAN 0x82 //added in fw 1.17
#define RPLIDAR_CMD_HQ_SCAN 0x83 //added in fw 1.24
#define RPLIDAR_CMD_GET_LIDAR_CONF 0x84 //added in fw 1.24
#define RPLIDAR_CMD_SET_LIDAR_CONF 0x85 //added in fw 1.24
//add for A2 to set RPLIDAR motor pwm when using accessory board
#define RPLIDAR_CMD_SET_MOTOR_PWM 0xF0
#define RPLIDAR_CMD_GET_ACC_BOARD_FLAG 0xFF
......@@ -67,12 +71,34 @@
// Payloads
// ------------------------------------------
#define RPLIDAR_EXPRESS_SCAN_MODE_NORMAL 0
#define RPLIDAR_EXPRESS_SCAN_MODE_FIXANGLE 1
#define RPLIDAR_EXPRESS_SCAN_MODE_FIXANGLE 0 // won't been supported but keep to prevent build fail
//for express working flag(extending express scan protocol)
#define RPLIDAR_EXPRESS_SCAN_FLAG_BOOST 0x0001
#define RPLIDAR_EXPRESS_SCAN_FLAG_SUNLIGHT_REJECTION 0x0002
//for ultra express working flag
#define RPLIDAR_ULTRAEXPRESS_SCAN_FLAG_STD 0x0001
#define RPLIDAR_ULTRAEXPRESS_SCAN_FLAG_HIGH_SENSITIVITY 0x0002
#define RPLIDAR_HQ_SCAN_FLAG_CCW (0x1<<0)
#define RPLIDAR_HQ_SCAN_FLAG_RAW_ENCODER (0x1<<1)
#define RPLIDAR_HQ_SCAN_FLAG_RAW_DISTANCE (0x1<<2)
typedef struct _rplidar_payload_express_scan_t {
_u8 working_mode;
_u32 reserved;
_u16 working_flags;
_u16 param;
} __attribute__((packed)) rplidar_payload_express_scan_t;
typedef struct _rplidar_payload_hq_scan_t {
_u8 flag;
_u8 reserved[32];
} __attribute__((packed)) rplidar_payload_hq_scan_t;
typedef struct _rplidar_payload_get_scan_conf_t {
_u32 type;
_u8 reserved[32];
} __attribute__((packed)) rplidar_payload_get_scan_conf_t;
#define MAX_MOTOR_PWM 1023
#define DEFAULT_MOTOR_PWM 660
typedef struct _rplidar_payload_motor_pwm_t {
......@@ -91,9 +117,16 @@ typedef struct _rplidar_payload_acc_board_flag_t {
#define RPLIDAR_ANS_TYPE_MEASUREMENT 0x81
// Added in FW ver 1.17
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED 0x82
#define RPLIDAR_ANS_TYPE_MEASUREMENT_HQ 0x83
// Added in FW ver 1.17
#define RPLIDAR_ANS_TYPE_SAMPLE_RATE 0x15
//added in FW ver 1.23alpha
#define RPLIDAR_ANS_TYPE_MEASUREMENT_CAPSULED_ULTRA 0x84
//added in FW ver 1.24
#define RPLIDAR_ANS_TYPE_GET_LIDAR_CONF 0x20
#define RPLIDAR_ANS_TYPE_SET_LIDAR_CONF 0x21
#define RPLIDAR_ANS_TYPE_ACC_BOARD_FLAG 0xFF
......@@ -109,6 +142,9 @@ typedef struct _rplidar_response_acc_board_flag_t {
#define RPLIDAR_RESP_MEASUREMENT_SYNCBIT (0x1<<0)
#define RPLIDAR_RESP_MEASUREMENT_QUALITY_SHIFT 2
#define RPLIDAR_RESP_HQ_FLAG_SYNCBIT (0x1<<0)
#define RPLIDAR_RESP_MEASUREMENT_CHECKBIT (0x1<<0)
#define RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT 1
......@@ -137,6 +173,8 @@ typedef struct _rplidar_response_cabin_nodes_t {
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_1 0xA
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNC_2 0x5
#define RPLIDAR_RESP_MEASUREMENT_HQ_SYNC 0xA5
#define RPLIDAR_RESP_MEASUREMENT_EXP_SYNCBIT (0x1<<15)
typedef struct _rplidar_response_capsule_measurement_nodes_t {
......@@ -145,6 +183,71 @@ typedef struct _rplidar_response_capsule_measurement_nodes_t {
_u16 start_angle_sync_q6;
rplidar_response_cabin_nodes_t cabins[16];
} __attribute__((packed)) rplidar_response_capsule_measurement_nodes_t;
// ext1 : x2 boost mode
#define RPLIDAR_RESP_MEASUREMENT_EXP_ULTRA_MAJOR_BITS 12
#define RPLIDAR_RESP_MEASUREMENT_EXP_ULTRA_PREDICT_BITS 10
typedef struct _rplidar_response_ultra_cabin_nodes_t {
// 31 0
// | predict2 10bit | predict1 10bit | major 12bit |
_u32 combined_x3;
} __attribute__((packed)) rplidar_response_ultra_cabin_nodes_t;
typedef struct _rplidar_response_ultra_capsule_measurement_nodes_t {
_u8 s_checksum_1; // see [s_checksum_1]
_u8 s_checksum_2; // see [s_checksum_1]
_u16 start_angle_sync_q6;
rplidar_response_ultra_cabin_nodes_t ultra_cabins[32];
} __attribute__((packed)) rplidar_response_ultra_capsule_measurement_nodes_t;
typedef struct rplidar_response_measurement_node_hq_t {
_u16 angle_z_q14;
_u32 dist_mm_q2;
_u8 quality;
_u8 flag;
} __attribute__((packed)) rplidar_response_measurement_node_hq_t;
typedef struct _rplidar_response_hq_capsule_measurement_nodes_t{
_u8 sync_byte;
_u64 time_stamp;
rplidar_response_measurement_node_hq_t node_hq[16];
_u32 crc32;
}__attribute__((packed)) rplidar_response_hq_capsule_measurement_nodes_t;
# define RPLIDAR_CONF_SCAN_COMMAND_STD 0
# define RPLIDAR_CONF_SCAN_COMMAND_EXPRESS 1
# define RPLIDAR_CONF_SCAN_COMMAND_HQ 2
# define RPLIDAR_CONF_SCAN_COMMAND_BOOST 3
# define RPLIDAR_CONF_SCAN_COMMAND_STABILITY 4
# define RPLIDAR_CONF_SCAN_COMMAND_SENSITIVITY 5
#define RPLIDAR_CONF_ANGLE_RANGE 0x00000000
#define RPLIDAR_CONF_DESIRED_ROT_FREQ 0x00000001
#define RPLIDAR_CONF_SCAN_COMMAND_BITMAP 0x00000002
#define RPLIDAR_CONF_MIN_ROT_FREQ 0x00000004
#define RPLIDAR_CONF_MAX_ROT_FREQ 0x00000005
#define RPLIDAR_CONF_MAX_DISTANCE 0x00000060
#define RPLIDAR_CONF_SCAN_MODE_COUNT 0x00000070
#define RPLIDAR_CONF_SCAN_MODE_US_PER_SAMPLE 0x00000071
#define RPLIDAR_CONF_SCAN_MODE_MAX_DISTANCE 0x00000074
#define RPLIDAR_CONF_SCAN_MODE_ANS_TYPE 0x00000075
#define RPLIDAR_CONF_SCAN_MODE_TYPICAL 0x0000007C
#define RPLIDAR_CONF_SCAN_MODE_NAME 0x0000007F
#define RPLIDAR_EXPRESS_SCAN_STABILITY_BITMAP 4
#define RPLIDAR_EXPRESS_SCAN_SENSITIVITY_BITMAP 5
typedef struct _rplidar_response_get_lidar_conf{
_u32 type;
_u8 payload[0];
}__attribute__((packed)) rplidar_response_get_lidar_conf_t;
typedef struct _rplidar_response_set_lidar_conf{
_u32 result;
}__attribute__((packed)) rplidar_response_set_lidar_conf_t;
typedef struct _rplidar_response_device_info_t {
_u8 model;
......@@ -158,6 +261,25 @@ typedef struct _rplidar_response_device_health_t {
_u16 error_code;
} __attribute__((packed)) rplidar_response_device_health_t;
// Definition of the variable bit scale encoding mechanism
#define RPLIDAR_VARBITSCALE_X2_SRC_BIT 9
#define RPLIDAR_VARBITSCALE_X4_SRC_BIT 11
#define RPLIDAR_VARBITSCALE_X8_SRC_BIT 12
#define RPLIDAR_VARBITSCALE_X16_SRC_BIT 14
#define RPLIDAR_VARBITSCALE_X2_DEST_VAL 512
#define RPLIDAR_VARBITSCALE_X4_DEST_VAL 1280
#define RPLIDAR_VARBITSCALE_X8_DEST_VAL 1792
#define RPLIDAR_VARBITSCALE_X16_DEST_VAL 3328
#define RPLIDAR_VARBITSCALE_GET_SRC_MAX_VAL_BY_BITS(_BITS_) \
( (((0x1<<(_BITS_)) - RPLIDAR_VARBITSCALE_X16_DEST_VAL)<<4) + \
((RPLIDAR_VARBITSCALE_X16_DEST_VAL - RPLIDAR_VARBITSCALE_X8_DEST_VAL)<<3) + \
((RPLIDAR_VARBITSCALE_X8_DEST_VAL - RPLIDAR_VARBITSCALE_X4_DEST_VAL)<<2) + \
((RPLIDAR_VARBITSCALE_X4_DEST_VAL - RPLIDAR_VARBITSCALE_X2_DEST_VAL)<<1) + \
RPLIDAR_VARBITSCALE_X2_DEST_VAL - 1)
#if defined(_WIN32)
#pragma pack()
#endif
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -60,5 +60,5 @@
#include <sys/select.h>
#include <time.h>
#include "arch/linux/timer.h"
#include "timer.h"
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -33,10 +33,37 @@
*/
#include "arch/linux/arch_linux.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <assert.h>
// linux specific
#include <errno.h>
#include <fcntl.h>
#include <time.h>
#include "hal/types.h"
#include "arch/linux/net_serial.h"
#include <termios.h>
#include <sys/select.h>
#include <algorithm>
//__GNUC__
#if defined(__GNUC__)
// for Linux extension
#include <asm/ioctls.h>
#include <asm/termbits.h>
#include <sys/ioctl.h>
extern "C" int tcflush(int fildes, int queue_selector);
#else
// for other standard UNIX
#include <termios.h>
#include <sys/ioctl.h>
#endif
namespace rp{ namespace arch{ namespace net{
raw_serial::raw_serial()
......@@ -75,10 +102,17 @@ bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
if (serial_fd == -1) return false;
#if !defined(__GNUC__)
// for standard UNIX
struct termios options, oldopt;
tcgetattr(serial_fd, &oldopt);
bzero(&options,sizeof(struct termios));
// enable rx and tx
options.c_cflag |= (CLOCAL | CREAD);
_u32 termbaud = getTermBaudBitmap(baudrate);
if (termbaud == (_u32)-1) {
......@@ -87,13 +121,10 @@ bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
}
cfsetispeed(&options, termbaud);
cfsetospeed(&options, termbaud);
// enable rx and tx
options.c_cflag |= (CLOCAL | CREAD);
options.c_cflag &= ~PARENB; //no checkbit
options.c_cflag &= ~CSTOPB; //1bit stop bit
options.c_cflag &= ~CRTSCTS; //no flow control
options.c_cflag &= ~CSIZE;
options.c_cflag |= CS8; /* Select 8 data bits */
......@@ -108,24 +139,88 @@ bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
// raw output mode
options.c_oflag &= ~OPOST;
tcflush(serial_fd,TCIFLUSH);
if (fcntl(serial_fd, F_SETFL, FNDELAY))
if (tcsetattr(serial_fd, TCSANOW, &options))
{
close();
return false;
}
if (tcsetattr(serial_fd, TCSANOW, &options))
#else
// using Linux extension ...
struct termios2 tio;
ioctl(serial_fd, TCGETS2, &tio);
bzero(&tio, sizeof(struct termios2));
tio.c_cflag = BOTHER;
tio.c_cflag |= (CLOCAL | CREAD | CS8); //8 bit no hardware handshake
tio.c_cflag &= ~CSTOPB; //1 stop bit
tio.c_cflag &= ~CRTSCTS; //No CTS
tio.c_cflag &= ~PARENB; //No Parity
#ifdef CNEW_RTSCTS
tio.c_cflag &= ~CNEW_RTSCTS; // no hw flow control
#endif
tio.c_iflag &= ~(IXON | IXOFF | IXANY); // no sw flow control
tio.c_cc[VMIN] = 0; //min chars to read
tio.c_cc[VTIME] = 0; //time in 1/10th sec wait
tio.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
// raw output mode
tio.c_oflag &= ~OPOST;
tio.c_ispeed = baudrate;
tio.c_ospeed = baudrate;
ioctl(serial_fd, TCSETS2, &tio);
#endif
tcflush(serial_fd, TCIFLUSH);
if (fcntl(serial_fd, F_SETFL, FNDELAY))
{
close();
return false;
}
_is_serial_opened = true;
_operation_aborted = false;
//Clear the DTR bit to let the motor spin
clearDTR();
do {
// create self pipeline for wait cancellation
if (pipe(_selfpipe) == -1) break;
int flags = fcntl(_selfpipe[0], F_GETFL);
if (flags == -1)
break;
flags |= O_NONBLOCK; /* Make read end nonblocking */
if (fcntl(_selfpipe[0], F_SETFL, flags) == -1)
break;
flags = fcntl(_selfpipe[1], F_GETFL);
if (flags == -1)
break;
flags |= O_NONBLOCK; /* Make write end nonblocking */
if (fcntl(_selfpipe[1], F_SETFL, flags) == -1)
break;
} while (0);
return true;
}
......@@ -136,6 +231,15 @@ void raw_serial::close()
::close(serial_fd);
serial_fd = -1;
if (_selfpipe[0] != -1)
::close(_selfpipe[0]);
if (_selfpipe[1] != -1)
::close(_selfpipe[1]);
_selfpipe[0] = _selfpipe[1] = -1;
_operation_aborted = false;
_is_serial_opened = false;
}
......@@ -206,7 +310,11 @@ int raw_serial::waitfordata(size_t data_count, _u32 timeout, size_t * returned_s
/* Initialize the input set */
FD_ZERO(&input_set);
FD_SET(serial_fd, &input_set);
max_fd = serial_fd + 1;
if (_selfpipe[0] != -1)
FD_SET(_selfpipe[0], &input_set);
max_fd = std::max<int>(serial_fd, _selfpipe[0]) + 1;
/* Initialize the timeout structure */
timeout_val.tv_sec = timeout / 1000;
......@@ -229,15 +337,32 @@ int raw_serial::waitfordata(size_t data_count, _u32 timeout, size_t * returned_s
if (n < 0)
{
// select error
*returned_size = 0;
return ANS_DEV_ERR;
}
else if (n == 0)
{
// time out
*returned_size =0;
return ANS_TIMEOUT;
}
else
{
if (FD_ISSET(_selfpipe[0], &input_set)) {
// require aborting the current operation
int ch;
for (;;) {
if (::read(_selfpipe[0], &ch, 1) == -1) {
break;
}
}
// treat as timeout
*returned_size = 0;
return ANS_TIMEOUT;
}
// data avaliable
assert (FD_ISSET(serial_fd, &input_set));
......@@ -288,12 +413,20 @@ void raw_serial::clearDTR()
void raw_serial::_init()
{
serial_fd = 0;
serial_fd = -1;
_portName[0] = 0;
required_tx_cnt = required_rx_cnt = 0;
_operation_aborted = false;
_selfpipe[0] = _selfpipe[1] = -1;
}
void raw_serial::cancelOperation()
{
_operation_aborted = true;
if (_selfpipe[1] == -1) return;
::write(_selfpipe[1], "x", 1);
}
_u32 raw_serial::getTermBaudBitmap(_u32 baud)
{
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -67,6 +67,9 @@ public:
virtual void clearDTR();
_u32 getTermBaudBitmap(_u32 baud);
virtual void cancelOperation();
protected:
bool open(const char * portname, uint32_t baudrate, uint32_t flags = 0);
void _init();
......@@ -79,6 +82,9 @@ protected:
size_t required_tx_cnt;
size_t required_rx_cnt;
int _selfpipe[2];
bool _operation_aborted;
};
}}}
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -34,7 +34,7 @@
#pragma once
#include "rptypes.h"
#include "hal/types.h"
#include <unistd.h>
static inline void delay(_word_size_t ms){
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -82,6 +82,7 @@ bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
_u32 termbaud = getTermBaudBitmap(baudrate);
if (termbaud == (_u32)-1) {
fprintf(stderr, "Baudrate %d is not supported on macOS\r\n", baudrate);
close();
return false;
}
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -31,36 +31,36 @@
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#pragma once
#pragma warning (disable: 4996)
#define _CRT_SECURE_NO_WARNINGS
#ifndef WINVER
#define WINVER 0x0500
#endif
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0501
#endif
#ifndef _WIN32_IE
#define _WIN32_IE 0x0501
#endif
#ifndef _RICHEDIT_VER
#define _RICHEDIT_VER 0x0200
#endif
#include <stddef.h>
#include <stdio.h>
#include <windows.h>
#include <stdlib.h> //for memcpy etc..
#include <process.h>
#include <direct.h>
#include "timer.h"
#pragma once
#pragma warning (disable: 4996)
#define _CRT_SECURE_NO_WARNINGS
#ifndef WINVER
#define WINVER 0x0500
#endif
#ifndef _WIN32_WINNT
#define _WIN32_WINNT 0x0501
#endif
#ifndef _WIN32_IE
#define _WIN32_IE 0x0501
#endif
#ifndef _RICHEDIT_VER
#define _RICHEDIT_VER 0x0200
#endif
#include <stddef.h>
#include <stdio.h>
#include <windows.h>
#include <stdlib.h> //for memcpy etc..
#include <process.h>
#include <direct.h>
#include "timer.h"
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -31,56 +31,56 @@
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#pragma once
#include "hal/abs_rxtx.h"
namespace rp{ namespace arch{ namespace net{
class raw_serial : public rp::hal::serial_rxtx
{
public:
enum{
SERIAL_RX_BUFFER_SIZE = 512,
SERIAL_TX_BUFFER_SIZE = 128,
SERIAL_RX_TIMEOUT = 2000,
SERIAL_TX_TIMEOUT = 2000,
};
raw_serial();
virtual ~raw_serial();
virtual bool bind(const char * portname, _u32 baudrate, _u32 flags = 0);
virtual bool open();
virtual void close();
virtual void flush( _u32 flags);
virtual int waitfordata(size_t data_count,_u32 timeout = -1, size_t * returned_size = NULL);
virtual int senddata(const unsigned char * data, size_t size);
virtual int recvdata(unsigned char * data, size_t size);
virtual int waitforsent(_u32 timeout = -1, size_t * returned_size = NULL);
virtual int waitforrecv(_u32 timeout = -1, size_t * returned_size = NULL);
virtual size_t rxqueue_count();
virtual void setDTR();
virtual void clearDTR();
protected:
bool open(const char * portname, _u32 baudrate, _u32 flags);
void _init();
char _portName[20];
uint32_t _baudrate;
uint32_t _flags;
OVERLAPPED _ro, _wo;
OVERLAPPED _wait_o;
volatile HANDLE _serial_handle;
DCB _dcb;
COMMTIMEOUTS _co;
};
}}}
#pragma once
#include "hal/abs_rxtx.h"
namespace rp{ namespace arch{ namespace net{
class raw_serial : public rp::hal::serial_rxtx
{
public:
enum{
SERIAL_RX_BUFFER_SIZE = 512,
SERIAL_TX_BUFFER_SIZE = 128,
SERIAL_RX_TIMEOUT = 2000,
SERIAL_TX_TIMEOUT = 2000,
};
raw_serial();
virtual ~raw_serial();
virtual bool bind(const char * portname, _u32 baudrate, _u32 flags = 0);
virtual bool open();
virtual void close();
virtual void flush( _u32 flags);
virtual int waitfordata(size_t data_count,_u32 timeout = -1, size_t * returned_size = NULL);
virtual int senddata(const unsigned char * data, size_t size);
virtual int recvdata(unsigned char * data, size_t size);
virtual int waitforsent(_u32 timeout = -1, size_t * returned_size = NULL);
virtual int waitforrecv(_u32 timeout = -1, size_t * returned_size = NULL);
virtual size_t rxqueue_count();
virtual void setDTR();
virtual void clearDTR();
protected:
bool open(const char * portname, _u32 baudrate, _u32 flags);
void _init();
char _portName[20];
uint32_t _baudrate;
uint32_t _flags;
OVERLAPPED _ro, _wo;
OVERLAPPED _wait_o;
volatile HANDLE _serial_handle;
DCB _dcb;
COMMTIMEOUTS _co;
};
}}}
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -31,32 +31,32 @@
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#include "sdkcommon.h"
#include <mmsystem.h>
#pragma comment(lib, "Winmm.lib")
namespace rp{ namespace arch{
static LARGE_INTEGER _current_freq;
void HPtimer_reset()
{
BOOL ans=QueryPerformanceFrequency(&_current_freq);
_current_freq.QuadPart/=1000;
}
_u32 getHDTimer()
{
LARGE_INTEGER current;
QueryPerformanceCounter(&current);
return (_u32)(current.QuadPart/_current_freq.QuadPart);
}
BEGIN_STATIC_CODE(timer_cailb)
{
HPtimer_reset();
}END_STATIC_CODE(timer_cailb)
}}
#include "sdkcommon.h"
#include <mmsystem.h>
#pragma comment(lib, "Winmm.lib")
namespace rp{ namespace arch{
static LARGE_INTEGER _current_freq;
void HPtimer_reset()
{
BOOL ans=QueryPerformanceFrequency(&_current_freq);
_current_freq.QuadPart/=1000;
}
_u32 getHDTimer()
{
LARGE_INTEGER current;
QueryPerformanceCounter(&current);
return (_u32)(current.QuadPart/_current_freq.QuadPart);
}
BEGIN_STATIC_CODE(timer_cailb)
{
HPtimer_reset();
}END_STATIC_CODE(timer_cailb)
}}
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -31,17 +31,17 @@
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#pragma once
#include "rptypes.h"
#define delay(x) ::Sleep(x)
namespace rp{ namespace arch{
void HPtimer_reset();
_u32 getHDTimer();
}}
#define getms() rp::arch::getHDTimer()
#pragma once
#include "hal/types.h"
#define delay(x) ::Sleep(x)
namespace rp{ namespace arch{
void HPtimer_reset();
_u32 getHDTimer();
}}
#define getms() rp::arch::getHDTimer()
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -31,114 +31,114 @@
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#include "sdkcommon.h"
#include <process.h>
namespace rp{ namespace hal{
Thread Thread::create(thread_proc_t proc, void * data)
{
Thread newborn(proc, data);
newborn._handle = (_word_size_t)(
_beginthreadex(NULL, 0, (unsigned int (_stdcall * )( void * ))proc,
data, 0, NULL));
return newborn;
}
u_result Thread::terminate()
{
if (!this->_handle) return RESULT_OK;
if (TerminateThread( reinterpret_cast<HANDLE>(this->_handle), -1))
{
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
this->_handle = NULL;
return RESULT_OK;
}else
{
return RESULT_OPERATION_FAIL;
}
}
u_result Thread::setPriority( priority_val_t p)
{
if (!this->_handle) return RESULT_OPERATION_FAIL;
int win_priority = THREAD_PRIORITY_NORMAL;
switch(p)
{
case PRIORITY_REALTIME:
win_priority = THREAD_PRIORITY_TIME_CRITICAL;
break;
case PRIORITY_HIGH:
win_priority = THREAD_PRIORITY_HIGHEST;
break;
case PRIORITY_NORMAL:
win_priority = THREAD_PRIORITY_NORMAL;
break;
case PRIORITY_LOW:
win_priority = THREAD_PRIORITY_LOWEST;
break;
case PRIORITY_IDLE:
win_priority = THREAD_PRIORITY_IDLE;
break;
}
if (SetThreadPriority(reinterpret_cast<HANDLE>(this->_handle), win_priority))
{
return RESULT_OK;
}
return RESULT_OPERATION_FAIL;
}
Thread::priority_val_t Thread::getPriority()
{
if (!this->_handle) return PRIORITY_NORMAL;
int win_priority = ::GetThreadPriority(reinterpret_cast<HANDLE>(this->_handle));
if (win_priority == THREAD_PRIORITY_ERROR_RETURN)
{
return PRIORITY_NORMAL;
}
if (win_priority >= THREAD_PRIORITY_TIME_CRITICAL )
{
return PRIORITY_REALTIME;
}
else if (win_priority<THREAD_PRIORITY_TIME_CRITICAL && win_priority>=THREAD_PRIORITY_ABOVE_NORMAL)
{
return PRIORITY_HIGH;
}
else if (win_priority<THREAD_PRIORITY_ABOVE_NORMAL && win_priority>THREAD_PRIORITY_BELOW_NORMAL)
{
return PRIORITY_NORMAL;
}else if (win_priority<=THREAD_PRIORITY_BELOW_NORMAL && win_priority>THREAD_PRIORITY_IDLE)
{
return PRIORITY_LOW;
}else if (win_priority<=THREAD_PRIORITY_IDLE)
{
return PRIORITY_IDLE;
}
return PRIORITY_NORMAL;
}
u_result Thread::join(unsigned long timeout)
{
if (!this->_handle) return RESULT_OK;
switch ( WaitForSingleObject(reinterpret_cast<HANDLE>(this->_handle), timeout))
{
case WAIT_OBJECT_0:
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
this->_handle = NULL;
return RESULT_OK;
case WAIT_ABANDONED:
return RESULT_OPERATION_FAIL;
case WAIT_TIMEOUT:
return RESULT_OPERATION_TIMEOUT;
}
return RESULT_OK;
}
}}
#include "sdkcommon.h"
#include <process.h>
namespace rp{ namespace hal{
Thread Thread::create(thread_proc_t proc, void * data)
{
Thread newborn(proc, data);
newborn._handle = (_word_size_t)(
_beginthreadex(NULL, 0, (unsigned int (_stdcall * )( void * ))proc,
data, 0, NULL));
return newborn;
}
u_result Thread::terminate()
{
if (!this->_handle) return RESULT_OK;
if (TerminateThread( reinterpret_cast<HANDLE>(this->_handle), -1))
{
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
this->_handle = NULL;
return RESULT_OK;
}else
{
return RESULT_OPERATION_FAIL;
}
}
u_result Thread::setPriority( priority_val_t p)
{
if (!this->_handle) return RESULT_OPERATION_FAIL;
int win_priority = THREAD_PRIORITY_NORMAL;
switch(p)
{
case PRIORITY_REALTIME:
win_priority = THREAD_PRIORITY_TIME_CRITICAL;
break;
case PRIORITY_HIGH:
win_priority = THREAD_PRIORITY_HIGHEST;
break;
case PRIORITY_NORMAL:
win_priority = THREAD_PRIORITY_NORMAL;
break;
case PRIORITY_LOW:
win_priority = THREAD_PRIORITY_LOWEST;
break;
case PRIORITY_IDLE:
win_priority = THREAD_PRIORITY_IDLE;
break;
}
if (SetThreadPriority(reinterpret_cast<HANDLE>(this->_handle), win_priority))
{
return RESULT_OK;
}
return RESULT_OPERATION_FAIL;
}
Thread::priority_val_t Thread::getPriority()
{
if (!this->_handle) return PRIORITY_NORMAL;
int win_priority = ::GetThreadPriority(reinterpret_cast<HANDLE>(this->_handle));
if (win_priority == THREAD_PRIORITY_ERROR_RETURN)
{
return PRIORITY_NORMAL;
}
if (win_priority >= THREAD_PRIORITY_TIME_CRITICAL )
{
return PRIORITY_REALTIME;
}
else if (win_priority<THREAD_PRIORITY_TIME_CRITICAL && win_priority>=THREAD_PRIORITY_ABOVE_NORMAL)
{
return PRIORITY_HIGH;
}
else if (win_priority<THREAD_PRIORITY_ABOVE_NORMAL && win_priority>THREAD_PRIORITY_BELOW_NORMAL)
{
return PRIORITY_NORMAL;
}else if (win_priority<=THREAD_PRIORITY_BELOW_NORMAL && win_priority>THREAD_PRIORITY_IDLE)
{
return PRIORITY_LOW;
}else if (win_priority<=THREAD_PRIORITY_IDLE)
{
return PRIORITY_IDLE;
}
return PRIORITY_NORMAL;
}
u_result Thread::join(unsigned long timeout)
{
if (!this->_handle) return RESULT_OK;
switch ( WaitForSingleObject(reinterpret_cast<HANDLE>(this->_handle), timeout))
{
case WAIT_OBJECT_0:
CloseHandle(reinterpret_cast<HANDLE>(this->_handle));
this->_handle = NULL;
return RESULT_OK;
case WAIT_ABANDONED:
return RESULT_OPERATION_FAIL;
case WAIT_TIMEOUT:
return RESULT_OPERATION_TIMEOUT;
}
return RESULT_OK;
}
}}
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -34,7 +34,7 @@
#pragma once
#include "rptypes.h"
#include "hal/types.h"
namespace rp{ namespace hal{
......@@ -71,6 +71,7 @@ public:
virtual void setDTR() = 0;
virtual void clearDTR() = 0;
virtual void cancelOperation() {}
virtual bool isOpened()
{
......
#ifndef _INFRA_HAL_ASSERT_H
#define _INFRA_HAL_ASSERT_H
#ifdef WIN32
#include <crtdbg.h>
#ifndef assert
#define assert(x) _ASSERT(x)
#endif
#elif defined(_AVR_)
#define assert(x)
#elif defined(__GNUC__)
#ifndef assert
#define assert(x)
#endif
#else
#error assert.h cannot identify your platform
#endif
#endif
/*
* RoboPeak Project
* Copyright 2009 - 2013
*
* RPOS - Byte Operations
*
*/
#pragma once
// byte swapping operations for compiling time
#define __static_byteswap_16(x) ((_u16)( \
(((_u16)(x) & (_u16)0x00FFU) << 8) | \
(((_u16)(x) & (_u16)0xFF00U) >> 8)))
#define __static_byteswap_32(x) ((_u32)( \
(((_u32)(x) & (_u32)0x000000FFUL) << 24) | \
(((_u32)(x) & (_u32)0x0000FF00UL) << 8) | \
(((_u32)(x) & (_u32)0x00FF0000UL) >> 8) | \
(((_u32)(x) & (_u32)0xFF000000UL) >> 24)))
#define __static_byteswap_64(x) ((_u64)( \
(((_u64)(x) & (_u64)0x00000000000000ffULL) << 56) | \
(((_u64)(x) & (_u64)0x000000000000ff00ULL) << 40) | \
(((_u64)(x) & (_u64)0x0000000000ff0000ULL) << 24) | \
(((_u64)(x) & (_u64)0x00000000ff000000ULL) << 8) | \
(((_u64)(x) & (_u64)0x000000ff00000000ULL) >> 8) | \
(((_u64)(x) & (_u64)0x0000ff0000000000ULL) >> 24) | \
(((_u64)(x) & (_u64)0x00ff000000000000ULL) >> 40) | \
(((_u64)(x) & (_u64)0xff00000000000000ULL) >> 56)))
#define __fast_swap(a, b) do { (a) ^= (b); (b) ^= (a); (a) ^= (b); } while(0)
static inline _u16 __byteswap_16(_u16 x)
{
#ifdef __arch_byteswap_16
return __arch_byteswap_16(x);
#else
return __static_byteswap_16(x);
#endif
}
static inline _u32 __byteswap_32(_u32 x)
{
#ifdef __arch_byteswap_32
return __arch_byteswap_32(x);
#else
return __static_byteswap_32(x);
#endif
}
static inline _u64 __byteswap_64(_u64 x)
{
#ifdef __arch_byteswap_64
return __arch_byteswap_64(x);
#else
return __static_byteswap_64(x);
#endif
}
#ifdef float
static inline float __byteswap_float(float x)
{
#ifdef __arch_byteswap_float
return __arch_byteswap_float(x);
#else
_u8 * raw = (_u8 *)&x;
__fast_swap(raw[0], raw[3]);
__fast_swap(raw[1], raw[2]);
return x;
#endif
}
#endif
#ifdef double
static inline double __byteswap_double(double x)
{
#ifdef __arch_byteswap_double
return __arch_byteswap_double(x);
#else
_u8 * raw = (_u8 *)&x;
__fast_swap(raw[0], raw[7]);
__fast_swap(raw[1], raw[6]);
__fast_swap(raw[2], raw[5]);
__fast_swap(raw[3], raw[4]);
return x;
#endif
}
#endif
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......@@ -34,7 +34,7 @@
#pragma once
#include "rptypes.h"
#include "hal/types.h"
#define CLASS_THREAD(c , x ) \
rp::hal::Thread::create_member<c, &c::x>(this )
......
This diff is collapsed.
......@@ -3,7 +3,7 @@
*
* Copyright (c) 2009 - 2014 RoboPeak Team
* http://www.robopeak.com
* Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
* Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
* http://www.slamtec.com
*
*/
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.