.. _program_listing_file__tmp_ws_src_dynamixel_sdk_dynamixel_sdk_include_dynamixel_sdk_group_bulk_read.h: Program Listing for File group_bulk_read.h ========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/dynamixel_sdk/dynamixel_sdk/include/dynamixel_sdk/group_bulk_read.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_GROUPBULKREAD_H_ #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ #include #include #include "port_handler.h" #include "packet_handler.h" namespace dynamixel { class WINDECLSPEC GroupBulkRead { private: PortHandler *port_; PacketHandler *ph_; std::vector id_list_; std::map address_list_; // std::map length_list_; // std::map data_list_; // std::map error_list_; // bool last_result_; bool is_param_changed_; uint8_t *param_; void makeParam(); public: GroupBulkRead(PortHandler *port, PacketHandler *ph); ~GroupBulkRead() { clearParam(); } PortHandler *getPortHandler() { return port_; } PacketHandler *getPacketHandler() { return ph_; } bool addParam (uint8_t id, uint16_t start_address, uint16_t data_length); void removeParam (uint8_t id); void clearParam (); int txPacket(); int rxPacket(); int txRxPacket(); bool isAvailable (uint8_t id, uint16_t address, uint16_t data_length); uint32_t getData (uint8_t id, uint16_t address, uint16_t data_length); bool getError (uint8_t id, uint8_t* error); }; } #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKREAD_H_ */