include
dynamixel_sdk
port_handler_windows.h
Go to the documentation of this file.
1
/*******************************************************************************
2
* Copyright 2017 ROBOTIS CO., LTD.
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
*
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*******************************************************************************/
16
21
22
#ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_
23
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_
24
25
#include <Windows.h>
26
27
#include "
port_handler.h
"
28
29
namespace
dynamixel
30
{
31
35
class
WINDECLSPEC
PortHandlerWindows
:
public
PortHandler
36
{
37
private
:
38
HANDLE
serial_handle_
;
39
LARGE_INTEGER
freq_
, counter_;
40
41
int
baudrate_
;
42
char
port_name_[100];
43
44
double
packet_start_time_
;
45
double
packet_timeout_
;
46
double
tx_time_per_byte_
;
47
48
bool
setupPort(
const
int
baudrate);
49
50
double
getCurrentTime();
51
double
getTimeSinceStart();
52
53
public
:
58
PortHandlerWindows
(
const
char
*port_name);
59
64
virtual
~PortHandlerWindows
() { closePort(); }
65
71
bool
openPort();
72
77
void
closePort();
78
83
void
clearPort();
84
90
void
setPortName(
const
char
*port_name);
91
97
char
*getPortName();
98
107
bool
setBaudRate(
const
int
baudrate);
108
114
int
getBaudRate();
115
122
int
getBytesAvailable();
123
134
int
readPort(uint8_t *packet,
int
length);
135
146
int
writePort(uint8_t *packet,
int
length);
147
153
void
setPacketTimeout(uint16_t packet_length);
154
160
void
setPacketTimeout(
double
msec);
161
166
bool
isPacketTimeout();
167
};
168
169
}
170
171
172
#endif
/* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_WINDOWS_PORTHANDLERWINDOWS_H_ */
dynamixel::PortHandlerWindows::~PortHandlerWindows
virtual ~PortHandlerWindows()
The function that closes the port @description The function calls PortHandlerWindows::closePort() to ...
Definition:
port_handler_windows.h:64
dynamixel::PortHandlerWindows::packet_timeout_
double packet_timeout_
Definition:
port_handler_windows.h:45
dynamixel::PortHandlerWindows::packet_start_time_
double packet_start_time_
Definition:
port_handler_windows.h:44
dynamixel
Definition:
group_bulk_read.h:31
dynamixel::PortHandler
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition:
port_handler.h:56
dynamixel::PortHandlerWindows::baudrate_
int baudrate_
Definition:
port_handler_windows.h:41
dynamixel::PortHandlerWindows::freq_
LARGE_INTEGER freq_
Definition:
port_handler_windows.h:39
dynamixel::PortHandlerWindows::serial_handle_
HANDLE serial_handle_
Definition:
port_handler_windows.h:38
dynamixel::PortHandlerWindows
The class for control port in Windows.
Definition:
port_handler_windows.h:35
dynamixel::PortHandlerWindows::tx_time_per_byte_
double tx_time_per_byte_
Definition:
port_handler_windows.h:46
port_handler.h
dynamixel_sdk
Author(s): Gilbert
, Zerom
, Darby Lim
, Leon
autogenerated on Wed Mar 2 2022 00:13:50