group_bulk_write.h
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * Copyright 2017 ROBOTIS CO., LTD.
00003 *
00004 * Licensed under the Apache License, Version 2.0 (the "License");
00005 * you may not use this file except in compliance with the License.
00006 * You may obtain a copy of the License at
00007 *
00008 *     http://www.apache.org/licenses/LICENSE-2.0
00009 *
00010 * Unless required by applicable law or agreed to in writing, software
00011 * distributed under the License is distributed on an "AS IS" BASIS,
00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013 * See the License for the specific language governing permissions and
00014 * limitations under the License.
00015 *******************************************************************************/
00016 
00021 
00022 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_
00023 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_
00024 
00025 
00026 #include <map>
00027 #include <vector>
00028 #include "port_handler.h"
00029 #include "packet_handler.h"
00030 
00031 namespace dynamixel
00032 {
00033 
00037 class WINDECLSPEC GroupBulkWrite
00038 {
00039  private:
00040   PortHandler    *port_;
00041   PacketHandler  *ph_;
00042 
00043   std::vector<uint8_t>            id_list_;
00044   std::map<uint8_t, uint16_t>     address_list_;  // <id, start_address>
00045   std::map<uint8_t, uint16_t>     length_list_;   // <id, data_length>
00046   std::map<uint8_t, uint8_t *>    data_list_;     // <id, data>
00047 
00048   bool            is_param_changed_;
00049 
00050   uint8_t        *param_;
00051   uint16_t        param_length_;
00052 
00053   void    makeParam();
00054 
00055  public:
00061   GroupBulkWrite(PortHandler *port, PacketHandler *ph);
00062 
00066   ~GroupBulkWrite() { clearParam(); }
00067 
00072   PortHandler     *getPortHandler()   { return port_; }
00073 
00078   PacketHandler   *getPacketHandler() { return ph_; }
00079 
00089   bool    addParam    (uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data);
00090 
00095   void    removeParam (uint8_t id);
00096 
00107   bool    changeParam (uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data);
00108 
00112   void    clearParam  ();
00113 
00121   int     txPacket();
00122 };
00123 
00124 }
00125 
00126 
00127 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_ */


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:11