.. _program_listing_file__tmp_ws_src_dynamixel_sdk_dynamixel_sdk_include_dynamixel_sdk_port_handler_arduino.h: Program Listing for File port_handler_arduino.h =============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/dynamixel_sdk/dynamixel_sdk/include/dynamixel_sdk/port_handler_arduino.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /******************************************************************************* * Copyright 2017 ROBOTIS CO., LTD. * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. * You may obtain a copy of the License at * * http://www.apache.org/licenses/LICENSE-2.0 * * Unless required by applicable law or agreed to in writing, software * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. *******************************************************************************/ #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ #if defined(ARDUINO) || defined(__OPENCR__) || defined (__OPENCM904__) #include #endif #include "port_handler.h" namespace dynamixel { class PortHandlerArduino : public PortHandler { private: int socket_fd_; int baudrate_; char port_name_[100]; double packet_start_time_; double packet_timeout_; double tx_time_per_byte; #if defined(__OPENCM904__) UARTClass *p_dxl_serial; #endif bool setupPort(const int cflag_baud); double getCurrentTime(); double getTimeSinceStart(); int checkBaudrateAvailable(int baudrate); void setPowerOn(); void setPowerOff(); void setTxEnable(); void setTxDisable(); public: PortHandlerArduino(const char *port_name); virtual ~PortHandlerArduino() { closePort(); } bool openPort(); void closePort(); void clearPort(); void setPortName(const char *port_name); char *getPortName(); bool setBaudRate(const int baudrate); int getBaudRate(); int getBytesAvailable(); int readPort(uint8_t *packet, int length); int writePort(uint8_t *packet, int length); void setPacketTimeout(uint16_t packet_length); void setPacketTimeout(double msec); bool isPacketTimeout(); }; } #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_ARDUINO_PORTHANDLERARDUINO_H_ */