Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
dxl::DxlInterface Class Reference

#include <dxl_interface.h>

Public Types

enum  PortState { PORT_FAIL, BAUDRATE_FAIL, INVALID_PROTOCOL, SUCCESS }
 

Public Member Functions

bool broadcastPing (std::vector< uint8_t > result_vec, uint16_t protocol)
 
bool bulkWritePosition (std::vector< motor > &motors)
 
bool bulkWriteVelocity (std::vector< motor > &motors)
 
 DxlInterface ()
 
PortState openPort (std::string port_name, unsigned int baudrate, float protocol)
 
bool ping (motor &motor)
 
bool readMotorsError (std::vector< motor > &motors)
 
bool readMotorsLoad (std::vector< motor > &motors)
 
bool readMotorsPos (std::vector< motor > &motors)
 
bool readMotorsVel (std::vector< motor > &motors)
 
bool reboot (const motor &motor)
 
bool setMotorsLed (std::vector< dxl::motor > &motors, const led_color &color)
 
bool setTorque (motor &motor, bool flag)
 
 ~DxlInterface ()
 

Private Member Functions

bool loadProtocol (uint16_t protocol)
 

Private Attributes

dynamixel::PacketHandlerpkt_handler_
 
dynamixel::PortHandlerport_handler_
 
float protocol_
 

Detailed Description

Definition at line 116 of file dxl_interface.h.

Member Enumeration Documentation

Enumerator
PORT_FAIL 
BAUDRATE_FAIL 
INVALID_PROTOCOL 
SUCCESS 

Definition at line 128 of file dxl_interface.h.

Constructor & Destructor Documentation

dxl::DxlInterface::DxlInterface ( )

Definition at line 10 of file dxl_interface.cpp.

dxl::DxlInterface::~DxlInterface ( )

Definition at line 109 of file dxl_interface.cpp.

Member Function Documentation

bool dxl::DxlInterface::broadcastPing ( std::vector< uint8_t >  result_vec,
uint16_t  protocol 
)

Definition at line 99 of file dxl_interface.cpp.

bool dxl::DxlInterface::bulkWritePosition ( std::vector< motor > &  motors)

Definition at line 303 of file dxl_interface.cpp.

bool dxl::DxlInterface::bulkWriteVelocity ( std::vector< motor > &  motors)

Definition at line 260 of file dxl_interface.cpp.

bool dxl::DxlInterface::loadProtocol ( uint16_t  protocol)
private

Definition at line 34 of file dxl_interface.cpp.

DxlInterface::PortState dxl::DxlInterface::openPort ( std::string  port_name,
unsigned int  baudrate,
float  protocol 
)

Definition at line 15 of file dxl_interface.cpp.

bool dxl::DxlInterface::ping ( dxl::motor motor)

Definition at line 50 of file dxl_interface.cpp.

bool dxl::DxlInterface::readMotorsError ( std::vector< motor > &  motors)

Definition at line 189 of file dxl_interface.cpp.

bool dxl::DxlInterface::readMotorsLoad ( std::vector< motor > &  motors)

Definition at line 223 of file dxl_interface.cpp.

bool dxl::DxlInterface::readMotorsPos ( std::vector< motor > &  motors)

Definition at line 114 of file dxl_interface.cpp.

bool dxl::DxlInterface::readMotorsVel ( std::vector< motor > &  motors)

Definition at line 153 of file dxl_interface.cpp.

bool dxl::DxlInterface::reboot ( const motor motor)

Definition at line 84 of file dxl_interface.cpp.

bool dxl::DxlInterface::setMotorsLed ( std::vector< dxl::motor > &  motors,
const led_color color 
)

Definition at line 329 of file dxl_interface.cpp.

bool dxl::DxlInterface::setTorque ( dxl::motor motor,
bool  flag 
)

Definition at line 66 of file dxl_interface.cpp.

Member Data Documentation

dynamixel::PacketHandler* dxl::DxlInterface::pkt_handler_
private

Definition at line 120 of file dxl_interface.h.

dynamixel::PortHandler* dxl::DxlInterface::port_handler_
private

Definition at line 121 of file dxl_interface.h.

float dxl::DxlInterface::protocol_
private

Definition at line 122 of file dxl_interface.h.


The documentation for this class was generated from the following files:


dxl_interface
Author(s):
autogenerated on Wed Jan 3 2018 03:47:56