Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes
DxlROSConsole Class Reference

Console appliation example for CDynamixel and CDynamixelROS. More...

#include <console.h>

Inheritance diagram for DxlROSConsole:
Inheritance graph
[legend]

List of all members.

Public Types

typedef std::vector
< DxlROSCommand
CommandList
typedef std::vector
< CDxlGeneric * > 
MotorList

Public Member Functions

CDxlGenericcreateMotor ()
 Create new uninitialized motor object.
 DxlROSConsole ()
 > Heartbeat interval
void execute (std::string cmd)
 Execute console command.
CDxlGenericgetMotor ()
 Get current motor.
MotorListgetMotors ()
 Get motor list.
void init (char *path)
 Initialize node.
void setHeartbeatInterval (double interval)
 Set heartbeat interval.
void setMotor (int id)
 Switch motor.
void spin ()
 Spin.
 ~DxlROSConsole ()
 Destructor.

Static Public Member Functions

static void * spin_hb (void *obj)
 Heartbeat thread main function.

Protected Attributes

CommandList commands_
 Available commands.
double hb_interval_
pthread_t hb_thread_
 Heartbeat thread handle.
CDxlGenericmotor_
 Current motor interface.
MotorList motors_
 Motor interface list.
ros::NodeHandle nh_
 ROS node handle.
char * path_
 Path to shared_serial node.
LxSerial serial_port_
 Serial port interface.

Detailed Description

Console appliation example for CDynamixel and CDynamixelROS.

Definition at line 88 of file console.h.


Member Typedef Documentation

Definition at line 91 of file console.h.

typedef std::vector<CDxlGeneric*> DxlROSConsole::MotorList

Definition at line 92 of file console.h.


Constructor & Destructor Documentation

> Heartbeat interval

Constructor

Definition at line 106 of file console.h.

Destructor.

Delete motor interface, close serial port, and shut down node handle

Definition at line 114 of file console.h.


Member Function Documentation

Create new uninitialized motor object.

Definition at line 453 of file console.cpp.

void DxlROSConsole::execute ( std::string  cmd)

Execute console command.

Parameters:
cmdCommand to execute
Note:
Console must be locked.

Definition at line 565 of file console.cpp.

Get current motor.

Definition at line 134 of file console.h.

Get motor list.

Definition at line 147 of file console.h.

void DxlROSConsole::init ( char *  path)

Initialize node.

Parameters:
pathpath to shared_serial node

Definition at line 490 of file console.cpp.

void DxlROSConsole::setHeartbeatInterval ( double  interval)

Set heartbeat interval.

Parameters:
intervalInterval in [s].
Note:
Console must be locked.

Definition at line 691 of file console.cpp.

void DxlROSConsole::setMotor ( int  id)

Switch motor.

Parameters:
idMotor identifier
Note:
Creates new object if none of the current motors has this identifier.

Definition at line 470 of file console.cpp.

Spin.

Alternatively drives the motor clockwise and counterclockwise

Definition at line 623 of file console.cpp.

void * DxlROSConsole::spin_hb ( void *  obj) [static]

Heartbeat thread main function.

Parameters:
objpointer to DxlROSConsole

Definition at line 700 of file console.cpp.


Member Data Documentation

Available commands.

Definition at line 99 of file console.h.

double DxlROSConsole::hb_interval_ [protected]

Definition at line 102 of file console.h.

pthread_t DxlROSConsole::hb_thread_ [protected]

Heartbeat thread handle.

Definition at line 101 of file console.h.

Current motor interface.

Definition at line 96 of file console.h.

Motor interface list.

Definition at line 97 of file console.h.

ROS node handle.

Definition at line 95 of file console.h.

char* DxlROSConsole::path_ [protected]

Path to shared_serial node.

Definition at line 100 of file console.h.

Serial port interface.

Definition at line 98 of file console.h.


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


threemxl
Author(s):
autogenerated on Thu Jun 6 2019 21:10:52