RoboAide
Project to improve a DIY robotic arm used for mobility assistance
Public Member Functions | Private Attributes | List of all members
Dynamixel Class Reference

#include <dynamixel.h>

Public Member Functions

 Dynamixel (int idNumber, float ratio=1)
 
 ~Dynamixel ()
 
bool init ()
 Initialize Dynamixel servo motor and verify that it is reachable. More...
 
bool setOperatingMode ()
 Set the dynamixel in joint mode. More...
 
void moveMotor (int32_t pos)
 Set the goal position of the dynamixel. More...
 
int32_t getPosition ()
 Get the current position of the Dynamixel. More...
 
void torque (bool onoff)
 

Private Attributes

DynamixelWorkbench dxl_wb
 
const int BAUDRATE = 57600
 
int id
 Dynamixel id. More...
 
float gearRatio
 Gear ratio for the motor's joint. More...
 

Detailed Description

Definition at line 10 of file dynamixel.h.

Constructor & Destructor Documentation

Dynamixel::Dynamixel ( int  idNumber,
float  ratio = 1 
)

Definition at line 20 of file dynamixel.h.

Dynamixel::~Dynamixel ( )

Definition at line 26 of file dynamixel.h.

Member Function Documentation

int32_t Dynamixel::getPosition ( )

Get the current position of the Dynamixel.

Returns
pos : integer of the current position

Definition at line 126 of file dynamixel.h.

bool Dynamixel::init ( )

Initialize Dynamixel servo motor and verify that it is reachable.

Returns
success (bool)

Definition at line 33 of file dynamixel.h.

void Dynamixel::moveMotor ( int32_t  pos)

Set the goal position of the dynamixel.

Parameters
pos: integer of the goal position

Definition at line 116 of file dynamixel.h.

bool Dynamixel::setOperatingMode ( )

Set the dynamixel in joint mode.

Returns
success (bool)

Definition at line 88 of file dynamixel.h.

void Dynamixel::torque ( bool  onoff)

Definition at line 134 of file dynamixel.h.

Member Data Documentation

const int Dynamixel::BAUDRATE = 57600
private

Definition at line 13 of file dynamixel.h.

DynamixelWorkbench Dynamixel::dxl_wb
private

Definition at line 12 of file dynamixel.h.

float Dynamixel::gearRatio
private

Gear ratio for the motor's joint.

Definition at line 17 of file dynamixel.h.

int Dynamixel::id
private

Dynamixel id.

Definition at line 15 of file dynamixel.h.


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