Program Listing for File group_sync_write.h
↰ Return to documentation for file (/tmp/ws/src/dynamixel_sdk/dynamixel_sdk/include/dynamixel_sdk/group_sync_write.h
)
/*******************************************************************************
* 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_GROUPSYNCWRITE_H_
#define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_
#include <map>
#include <vector>
#include "port_handler.h"
#include "packet_handler.h"
namespace dynamixel
{
class WINDECLSPEC GroupSyncWrite
{
private:
PortHandler *port_;
PacketHandler *ph_;
std::vector<uint8_t> id_list_;
std::map<uint8_t, uint8_t* > data_list_; // <id, data>
bool is_param_changed_;
uint8_t *param_;
uint16_t start_address_;
uint16_t data_length_;
void makeParam();
public:
GroupSyncWrite(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length);
~GroupSyncWrite() { clearParam(); }
PortHandler *getPortHandler() { return port_; }
PacketHandler *getPacketHandler() { return ph_; }
bool addParam (uint8_t id, uint8_t *data);
void removeParam (uint8_t id);
bool changeParam (uint8_t id, uint8_t *data);
void clearParam ();
int txPacket();
};
}
#endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_ */